diff --git a/system/mrm_stop_operator/config/mrm_stop_operator.param.yaml b/system/mrm_stop_operator/config/mrm_stop_operator.param.yaml index 5dfbb2956d668..7043b61596f76 100644 --- a/system/mrm_stop_operator/config/mrm_stop_operator.param.yaml +++ b/system/mrm_stop_operator/config/mrm_stop_operator.param.yaml @@ -3,4 +3,3 @@ min_acceleration: -4.0 # min acceleration for sub ecu mrm stop [m/s^2] max_jerk: 5.0 # max jerk for sub ecu mrm stop [m/s^3] min_jerk: -5.0 # min jerk for sub ecu mrm stop [m/s^3] - diff --git a/system/mrm_stop_operator/src/mrm_stop_operator.cpp b/system/mrm_stop_operator/src/mrm_stop_operator.cpp index e858bc7b4a1dc..7abfd0a36d0bb 100644 --- a/system/mrm_stop_operator/src/mrm_stop_operator.cpp +++ b/system/mrm_stop_operator/src/mrm_stop_operator.cpp @@ -46,7 +46,7 @@ MrmStopOperator::MrmStopOperator(const rclcpp::NodeOptions & node_options) "~/output/velocity_limit_clear_command", rclcpp::QoS{10}.transient_local()); pub_mrm_state_ = create_publisher( - "~/output/mrm_state", rclcpp::QoS{1}.transient_local()); + "~/output/mrm_state", rclcpp::QoS{1}); // Timer