File tree 3 files changed +4
-4
lines changed
include/mpc_lateral_controller
trajectory_follower_node/include/trajectory_follower_node
3 files changed +4
-4
lines changed Original file line number Diff line number Diff line change @@ -54,7 +54,7 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
54
54
{
55
55
public:
56
56
// / \param node Reference to the node used only for the component and parameter initialization.
57
- explicit MpcLateralController (rclcpp::Node & node);
57
+ explicit MpcLateralController (rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater_ );
58
58
virtual ~MpcLateralController ();
59
59
60
60
private:
@@ -95,8 +95,6 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
95
95
// trajectory buffer for detecting new trajectory
96
96
std::deque<Trajectory> m_trajectory_buffer;
97
97
98
- diagnostic_updater::Updater diag_updater_{this }; // Diagnostic updater for publishing diagnostic data.
99
-
100
98
void setStatus (diagnostic_updater::DiagnosticStatusWrapper & stat, const bool & m_is_mpc_solved);
101
99
102
100
void setupDiag ();
Original file line number Diff line number Diff line change 35
35
namespace autoware ::motion::control::mpc_lateral_controller
36
36
{
37
37
38
- MpcLateralController::MpcLateralController (rclcpp::Node & node)
38
+ MpcLateralController::MpcLateralController (rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater_ )
39
39
: clock_(node.get_clock()), logger_(node.get_logger().get_child(" lateral_controller" ))
40
40
{
41
41
const auto dp_int = [&](const std::string & s) { return node.declare_parameter <int >(s); };
Original file line number Diff line number Diff line change @@ -73,6 +73,8 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node
73
73
double timeout_thr_sec_;
74
74
boost::optional<LongitudinalOutput> longitudinal_output_{boost::none};
75
75
76
+ std::shared_ptr<diagnostic_updater::Updater> diag_updater_{this }; // Diagnostic updater for publishing diagnostic data.
77
+
76
78
std::shared_ptr<trajectory_follower::LongitudinalControllerBase> longitudinal_controller_;
77
79
std::shared_ptr<trajectory_follower::LateralControllerBase> lateral_controller_;
78
80
You can’t perform that action at this time.
0 commit comments