Skip to content

Commit 5659be4

Browse files
committed
shared pointer added.
Signed-off-by: Zhe Shen <lucidshenzhe@gmail.com>
1 parent d3278b4 commit 5659be4

File tree

3 files changed

+4
-4
lines changed

3 files changed

+4
-4
lines changed

control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
5454
{
5555
public:
5656
/// \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_);
5858
virtual ~MpcLateralController();
5959

6060
private:
@@ -95,8 +95,6 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
9595
// trajectory buffer for detecting new trajectory
9696
std::deque<Trajectory> m_trajectory_buffer;
9797

98-
diagnostic_updater::Updater diag_updater_{this}; // Diagnostic updater for publishing diagnostic data.
99-
10098
void setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat, const bool & m_is_mpc_solved);
10199

102100
void setupDiag();

control/mpc_lateral_controller/src/mpc_lateral_controller.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535
namespace autoware::motion::control::mpc_lateral_controller
3636
{
3737

38-
MpcLateralController::MpcLateralController(rclcpp::Node & node)
38+
MpcLateralController::MpcLateralController(rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater_)
3939
: clock_(node.get_clock()), logger_(node.get_logger().get_child("lateral_controller"))
4040
{
4141
const auto dp_int = [&](const std::string & s) { return node.declare_parameter<int>(s); };

control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,8 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node
7373
double timeout_thr_sec_;
7474
boost::optional<LongitudinalOutput> longitudinal_output_{boost::none};
7575

76+
std::shared_ptr<diagnostic_updater::Updater> diag_updater_{this}; // Diagnostic updater for publishing diagnostic data.
77+
7678
std::shared_ptr<trajectory_follower::LongitudinalControllerBase> longitudinal_controller_;
7779
std::shared_ptr<trajectory_follower::LateralControllerBase> lateral_controller_;
7880

0 commit comments

Comments
 (0)