Skip to content

Commit d278c64

Browse files
committed
fix some scope issues
Signed-off-by: Zhe Shen <lucidshenzhe@gmail.com>
1 parent 4f6849e commit d278c64

File tree

2 files changed

+6
-5
lines changed

2 files changed

+6
-5
lines changed

control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
3333
#include "tier4_debug_msgs/msg/float32_stamped.hpp"
3434

35+
#include <diagnostic_updater/diagnostic_updater.hpp>
3536
#include <deque>
3637
#include <memory>
3738
#include <string>
@@ -91,9 +92,9 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
9192
// trajectory buffer for detecting new trajectory
9293
std::deque<Trajectory> m_trajectory_buffer;
9394

94-
Updater diag_updater_{this}; // Diagnostic updater for publishing diagnostic data.
95+
diagnostic_updater::Updater diag_updater_{this}; // Diagnostic updater for publishing diagnostic data.
9596

96-
void setStatus(DiagnosticStatusWrapper & stat, const bool & m_MPC_failed);
97+
void setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat, const bool & m_MPC_failed);
9798

9899
void setupDiag();
99100

control/mpc_lateral_controller/src/mpc_lateral_controller.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -230,13 +230,13 @@ std::shared_ptr<SteeringOffsetEstimator> MpcLateralController::createSteerOffset
230230
}
231231

232232
void MpcLateralController::setStatus(
233-
DiagnosticStatusWrapper & stat, const bool & is_mpc_solved)
233+
diagnostic_updater::DiagnosticStatusWrapper & stat, const bool & is_mpc_solved)
234234
{
235235
if (is_mpc_solved) {
236-
stat.summary(DiagnosticStatus::OK, "MPC succeeded.");
236+
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "MPC succeeded.");
237237
} else {
238238
const std::string & error_msg = "The MPC solver failed. Call MRM to stop the car.";
239-
stat.summary(DiagnosticStatus::ERROR, error_msg);
239+
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, error_msg);
240240
}
241241
}
242242

0 commit comments

Comments
 (0)