Skip to content

Commit cd86f0a

Browse files
authored
fix(autoware_pid_longitudinal_controller, autoware_trajectory_follower_node): unite diagnostic_updater_ in PID and MPC. (#7674)
* diag_updater_ added in PID Signed-off-by: Zhe Shen <lucidshenzhe@gmail.com> * correct the pointer form Signed-off-by: Zhe Shen <lucidshenzhe@gmail.com> * pre-commit Signed-off-by: Zhe Shen <lucidshenzhe@gmail.com> --------- Signed-off-by: Zhe Shen <lucidshenzhe@gmail.com>
1 parent 1cff7ad commit cd86f0a

File tree

3 files changed

+14
-10
lines changed

3 files changed

+14
-10
lines changed

control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
6464
{
6565
public:
6666
/// \param node Reference to the node used only for the component and parameter initialization.
67-
explicit PidLongitudinalController(rclcpp::Node & node);
67+
explicit PidLongitudinalController(
68+
rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater);
6869

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

238239
// Diagnostic
239-
240-
diagnostic_updater::Updater diagnostic_updater_;
240+
std::shared_ptr<diagnostic_updater::Updater>
241+
diag_updater_{}; // Diagnostic updater for publishing diagnostic data.
241242
struct DiagnosticData
242243
{
243244
double trans_deviation{0.0}; // translation deviation between nearest point and current_pose

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+8-6
Original file line numberDiff line numberDiff line change
@@ -27,14 +27,16 @@
2727

2828
namespace autoware::motion::control::pid_longitudinal_controller
2929
{
30-
PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
30+
PidLongitudinalController::PidLongitudinalController(
31+
rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater)
3132
: node_parameters_(node.get_node_parameters_interface()),
3233
clock_(node.get_clock()),
33-
logger_(node.get_logger().get_child("longitudinal_controller")),
34-
diagnostic_updater_(&node)
34+
logger_(node.get_logger().get_child("longitudinal_controller"))
3535
{
3636
using std::placeholders::_1;
3737

38+
diag_updater_ = diag_updater;
39+
3840
// parameters timer
3941
m_longitudinal_ctrl_period = node.get_parameter("ctrl_period").as_double();
4042

@@ -432,7 +434,7 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run(
432434
publishDebugData(ctrl_cmd, control_data);
433435

434436
// diagnostic
435-
diagnostic_updater_.force_update();
437+
diag_updater_->force_update();
436438

437439
return output;
438440
}
@@ -1150,8 +1152,8 @@ void PidLongitudinalController::updateDebugVelAcc(const ControlData & control_da
11501152

11511153
void PidLongitudinalController::setupDiagnosticUpdater()
11521154
{
1153-
diagnostic_updater_.setHardwareID("autoware_pid_longitudinal_controller");
1154-
diagnostic_updater_.add("control_state", this, &PidLongitudinalController::checkControlState);
1155+
diag_updater_->setHardwareID("autoware_pid_longitudinal_controller");
1156+
diag_updater_->add("control_state", this, &PidLongitudinalController::checkControlState);
11551157
}
11561158

11571159
void PidLongitudinalController::checkControlState(

control/autoware_trajectory_follower_node/src/controller_node.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control
5757
switch (longitudinal_controller_mode) {
5858
case LongitudinalControllerMode::PID: {
5959
longitudinal_controller_ =
60-
std::make_shared<pid_longitudinal_controller::PidLongitudinalController>(*this);
60+
std::make_shared<pid_longitudinal_controller::PidLongitudinalController>(
61+
*this, diag_updater_);
6162
break;
6263
}
6364
default:

0 commit comments

Comments
 (0)