diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp index 1f16bbc39bbbf..09399d1fa2dce 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -22,6 +22,8 @@ #include "autoware/trajectory_follower_base/lateral_controller_base.hpp" #include "rclcpp/rclcpp.hpp" +#include + #include "autoware_control_msgs/msg/lateral.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" @@ -52,7 +54,8 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase { public: /// \param node Reference to the node used only for the component and parameter initialization. - explicit MpcLateralController(rclcpp::Node & node); + explicit MpcLateralController( + rclcpp::Node & node, std::shared_ptr diag_updater); virtual ~MpcLateralController(); private: @@ -63,6 +66,9 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase rclcpp::Publisher::SharedPtr m_pub_debug_values; rclcpp::Publisher::SharedPtr m_pub_steer_offset; + std::shared_ptr + diag_updater_{}; // Diagnostic updater for publishing diagnostic data. + //!< @brief parameters for path smoothing TrajectoryFilteringParam m_trajectory_filtering_param; @@ -87,9 +93,16 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase // Flag indicating whether to keep the steering control until it converges. bool m_keep_steer_control_until_converged; + // MPC solver checker. + bool m_is_mpc_solved{true}; + // trajectory buffer for detecting new trajectory std::deque m_trajectory_buffer; + void setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); + + void setupDiag(); + std::unique_ptr m_mpc; // MPC object for trajectory following. // Check is mpc output converged diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 6aedb74e87c83..0661b439a3982 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -35,13 +35,16 @@ namespace autoware::motion::control::mpc_lateral_controller { -MpcLateralController::MpcLateralController(rclcpp::Node & node) +MpcLateralController::MpcLateralController( + rclcpp::Node & node, std::shared_ptr diag_updater) : clock_(node.get_clock()), logger_(node.get_logger().get_child("lateral_controller")) { const auto dp_int = [&](const std::string & s) { return node.declare_parameter(s); }; const auto dp_bool = [&](const std::string & s) { return node.declare_parameter(s); }; const auto dp_double = [&](const std::string & s) { return node.declare_parameter(s); }; + diag_updater_ = diag_updater; + m_mpc = std::make_unique(node); m_mpc->m_ctrl_period = node.get_parameter("ctrl_period").as_double(); @@ -152,6 +155,8 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) m_mpc->setLogger(logger_); m_mpc->setClock(clock_); + + setupDiag(); } MpcLateralController::~MpcLateralController() @@ -227,6 +232,24 @@ std::shared_ptr MpcLateralController::createSteerOffset return steering_offset_; } +void MpcLateralController::setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + if (m_is_mpc_solved) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "MPC succeeded."); + } else { + const std::string error_msg = "The MPC solver failed. Call MRM to stop the car."; + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, error_msg); + } +} + +void MpcLateralController::setupDiag() +{ + auto & d = diag_updater_; + d->setHardwareID("mpc_lateral_controller"); + + d->add("MPC_solve_checker", [&](auto & stat) { setStatus(stat); }); +} + trajectory_follower::LateralOutput MpcLateralController::run( trajectory_follower::InputData const & input_data) { @@ -255,6 +278,10 @@ trajectory_follower::LateralOutput MpcLateralController::run( const bool is_mpc_solved = m_mpc->calculateMPC( m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values); + m_is_mpc_solved = is_mpc_solved; // for diagnostic updater + + diag_updater_->force_update(); + // reset previous MPC result // Note: When a large deviation from the trajectory occurs, the optimization stops and // the vehicle will return to the path by re-planning the trajectory or external operation. diff --git a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp index 06873c31cc6cc..21d58748d31fa 100644 --- a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp +++ b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp @@ -30,6 +30,7 @@ #include #include #include +#include #include "autoware_control_msgs/msg/control.hpp" #include "autoware_control_msgs/msg/longitudinal.hpp" @@ -73,6 +74,10 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node double timeout_thr_sec_; boost::optional longitudinal_output_{boost::none}; + std::shared_ptr diag_updater_ = + std::make_shared( + this); // Diagnostic updater for publishing diagnostic data. + std::shared_ptr longitudinal_controller_; std::shared_ptr lateral_controller_; diff --git a/control/autoware_trajectory_follower_node/src/controller_node.cpp b/control/autoware_trajectory_follower_node/src/controller_node.cpp index 7876a38247bc9..274da6e9a5534 100644 --- a/control/autoware_trajectory_follower_node/src/controller_node.cpp +++ b/control/autoware_trajectory_follower_node/src/controller_node.cpp @@ -39,7 +39,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control getLateralControllerMode(declare_parameter("lateral_controller_mode")); switch (lateral_controller_mode) { case LateralControllerMode::MPC: { - lateral_controller_ = std::make_shared(*this); + lateral_controller_ = + std::make_shared(*this, diag_updater_); break; } case LateralControllerMode::PURE_PURSUIT: {