|
27 | 27 |
|
28 | 28 | namespace autoware::motion::control::pid_longitudinal_controller
|
29 | 29 | {
|
30 |
| -PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node) |
| 30 | +PidLongitudinalController::PidLongitudinalController( |
| 31 | + rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater) |
31 | 32 | : node_parameters_(node.get_node_parameters_interface()),
|
32 | 33 | 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")) |
35 | 35 | {
|
36 | 36 | using std::placeholders::_1;
|
37 | 37 |
|
| 38 | + diag_updater_ = diag_updater; |
| 39 | + |
38 | 40 | // parameters timer
|
39 | 41 | m_longitudinal_ctrl_period = node.get_parameter("ctrl_period").as_double();
|
40 | 42 |
|
@@ -432,7 +434,7 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run(
|
432 | 434 | publishDebugData(ctrl_cmd, control_data);
|
433 | 435 |
|
434 | 436 | // diagnostic
|
435 |
| - diagnostic_updater_.force_update(); |
| 437 | + diag_updater_->force_update(); |
436 | 438 |
|
437 | 439 | return output;
|
438 | 440 | }
|
@@ -1150,8 +1152,8 @@ void PidLongitudinalController::updateDebugVelAcc(const ControlData & control_da
|
1150 | 1152 |
|
1151 | 1153 | void PidLongitudinalController::setupDiagnosticUpdater()
|
1152 | 1154 | {
|
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); |
1155 | 1157 | }
|
1156 | 1158 |
|
1157 | 1159 | void PidLongitudinalController::checkControlState(
|
|
0 commit comments