diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp index dce631ce98224..f795a60dcefbb 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -97,7 +97,7 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase // trajectory buffer for detecting new trajectory std::deque m_trajectory_buffer; - void setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat, const bool & m_is_mpc_solved); + void setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); void setupDiag(); diff --git a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp index 65166553cfbeb..12a0d9c8620bb 100644 --- a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -232,7 +232,7 @@ std::shared_ptr MpcLateralController::createSteerOffset } void MpcLateralController::setStatus( - diagnostic_updater::DiagnosticStatusWrapper & stat, const bool & m_is_mpc_solved) + diagnostic_updater::DiagnosticStatusWrapper & stat) { if (m_is_mpc_solved) { stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "MPC succeeded."); @@ -249,7 +249,7 @@ void MpcLateralController::setupDiag() d->add("MPC_solve_checker", [&](auto & stat) { setStatus( - stat, m_is_mpc_solved); + stat); }); }