diff --git a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp index a61b2cfb55471..65166553cfbeb 100644 --- a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -245,9 +245,9 @@ void MpcLateralController::setStatus( void MpcLateralController::setupDiag() { auto & d = diag_updater_; - d.setHardwareID("mpc_lateral_controller"); + d->setHardwareID("mpc_lateral_controller"); - d.add("MPC_solve_checker", [&](auto & stat) { + d->add("MPC_solve_checker", [&](auto & stat) { setStatus( stat, m_is_mpc_solved); }); @@ -283,7 +283,7 @@ trajectory_follower::LateralOutput MpcLateralController::run( m_is_mpc_solved = is_mpc_solved; // for diagnostic updater - diag_updater_.force_update(); + diag_updater_->force_update(); // reset previous MPC result // Note: When a large deviation from the trajectory occurs, the optimization stops and diff --git a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp index 0c34fab892f3f..90df6d77a4782 100644 --- a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp +++ b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp" #include "autoware_auto_control_msgs/msg/longitudinal_command.hpp" @@ -73,7 +74,7 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node double timeout_thr_sec_; boost::optional longitudinal_output_{boost::none}; - std::shared_ptr diag_updater_{this}; // Diagnostic updater for publishing diagnostic data. + std::shared_ptr diag_updater_ = std::make_shared(this); // Diagnostic updater for publishing diagnostic data. std::shared_ptr longitudinal_controller_; std::shared_ptr lateral_controller_;