Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_pid_longitudinal_controller, autoware_trajectory_follower_node): unite diagnostic_updater_ in PID and MPC. #7674

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
{
public:
/// \param node Reference to the node used only for the component and parameter initialization.
explicit PidLongitudinalController(rclcpp::Node & node);
explicit PidLongitudinalController(
rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater);

private:
struct Motion
Expand Down Expand Up @@ -236,8 +237,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
std::shared_ptr<rclcpp::Time> m_last_running_time{std::make_shared<rclcpp::Time>(clock_->now())};

// Diagnostic

diagnostic_updater::Updater diagnostic_updater_;
std::shared_ptr<diagnostic_updater::Updater>
diag_updater_{}; // Diagnostic updater for publishing diagnostic data.
struct DiagnosticData
{
double trans_deviation{0.0}; // translation deviation between nearest point and current_pose
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc. All rights reserved.

Check notice on line 1 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 4.61 to 4.56, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -27,14 +27,16 @@

namespace autoware::motion::control::pid_longitudinal_controller
{
PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
PidLongitudinalController::PidLongitudinalController(
rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater)
: node_parameters_(node.get_node_parameters_interface()),
clock_(node.get_clock()),
logger_(node.get_logger().get_child("longitudinal_controller")),
diagnostic_updater_(&node)
logger_(node.get_logger().get_child("longitudinal_controller"))
{
using std::placeholders::_1;

diag_updater_ = diag_updater;

Check notice on line 39 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Large Method

diagnostic_updater_ is no longer above the threshold for lines of code. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
// parameters timer
m_longitudinal_ctrl_period = node.get_parameter("ctrl_period").as_double();

Expand Down Expand Up @@ -432,7 +434,7 @@
publishDebugData(ctrl_cmd, control_data);

// diagnostic
diagnostic_updater_.force_update();
diag_updater_->force_update();

return output;
}
Expand Down Expand Up @@ -1150,8 +1152,8 @@

void PidLongitudinalController::setupDiagnosticUpdater()
{
diagnostic_updater_.setHardwareID("autoware_pid_longitudinal_controller");
diagnostic_updater_.add("control_state", this, &PidLongitudinalController::checkControlState);
diag_updater_->setHardwareID("autoware_pid_longitudinal_controller");
diag_updater_->add("control_state", this, &PidLongitudinalController::checkControlState);
}

void PidLongitudinalController::checkControlState(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control
switch (longitudinal_controller_mode) {
case LongitudinalControllerMode::PID: {
longitudinal_controller_ =
std::make_shared<pid_longitudinal_controller::PidLongitudinalController>(*this);
std::make_shared<pid_longitudinal_controller::PidLongitudinalController>(
*this, diag_updater_);
break;
}
default:
Expand Down
Loading