File tree 2 files changed +5
-4
lines changed
autoware_mpc_lateral_controller/src
autoware_trajectory_follower_node/include/autoware_trajectory_follower_node
2 files changed +5
-4
lines changed Original file line number Diff line number Diff line change @@ -245,9 +245,9 @@ void MpcLateralController::setStatus(
245
245
void MpcLateralController::setupDiag ()
246
246
{
247
247
auto & d = diag_updater_;
248
- d. setHardwareID (" mpc_lateral_controller" );
248
+ d-> setHardwareID (" mpc_lateral_controller" );
249
249
250
- d. add (" MPC_solve_checker" , [&](auto & stat) {
250
+ d-> add (" MPC_solve_checker" , [&](auto & stat) {
251
251
setStatus (
252
252
stat, m_is_mpc_solved);
253
253
});
@@ -283,7 +283,7 @@ trajectory_follower::LateralOutput MpcLateralController::run(
283
283
284
284
m_is_mpc_solved = is_mpc_solved; // for diagnostic updater
285
285
286
- diag_updater_. force_update ();
286
+ diag_updater_-> force_update ();
287
287
288
288
// reset previous MPC result
289
289
// Note: When a large deviation from the trajectory occurs, the optimization stops and
Original file line number Diff line number Diff line change 30
30
#include < Eigen/Core>
31
31
#include < Eigen/Geometry>
32
32
#include < tier4_autoware_utils/ros/published_time_publisher.hpp>
33
+ #include < diagnostic_updater/diagnostic_updater.hpp>
33
34
34
35
#include " autoware_control_msgs/msg/control.hpp"
35
36
#include " autoware_control_msgs/msg/longitudinal.hpp"
@@ -73,7 +74,7 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node
73
74
double timeout_thr_sec_;
74
75
boost::optional<LongitudinalOutput> longitudinal_output_{boost::none};
75
76
76
- std::shared_ptr<diagnostic_updater::Updater> diag_updater_{ this } ; // Diagnostic updater for publishing diagnostic data.
77
+ std::shared_ptr<diagnostic_updater::Updater> diag_updater_ = std::make_shared<diagnostic_updater::Updater>( this ) ; // Diagnostic updater for publishing diagnostic data.
77
78
78
79
std::shared_ptr<trajectory_follower::LongitudinalControllerBase> longitudinal_controller_;
79
80
std::shared_ptr<trajectory_follower::LateralControllerBase> lateral_controller_;
You can’t perform that action at this time.
0 commit comments