File tree 3 files changed +18
-0
lines changed
3 files changed +18
-0
lines changed Original file line number Diff line number Diff line change 29
29
#include < autoware_vehicle_msgs/msg/control_mode_report.hpp>
30
30
#include < autoware_vehicle_msgs/msg/gear_command.hpp>
31
31
#include < autoware_vehicle_msgs/msg/hazard_lights_command.hpp>
32
+ #include < tier4_system_msgs/msg/emergency_holding_state.hpp>
32
33
#include < tier4_system_msgs/msg/mrm_behavior_status.hpp>
33
34
#include < tier4_system_msgs/msg/operation_mode_availability.hpp>
34
35
#include < tier4_system_msgs/srv/operate_mrm.hpp>
@@ -109,6 +110,10 @@ class MrmHandler : public rclcpp::Node
109
110
autoware_adapi_v1_msgs::msg::MrmState mrm_state_;
110
111
void publishMrmState ();
111
112
113
+ rclcpp::Publisher<tier4_system_msgs::msg::EmergencyHoldingState>::SharedPtr
114
+ pub_emergency_holding_;
115
+ void publishEmergencyHolding ();
116
+
112
117
// Clients
113
118
rclcpp::CallbackGroup::SharedPtr client_mrm_pull_over_group_;
114
119
rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_pull_over_;
Original file line number Diff line number Diff line change 12
12
<arg name =" output_gear" default =" /system/emergency/gear_cmd" />
13
13
<arg name =" output_hazard" default =" /system/emergency/hazard_lights_cmd" />
14
14
<arg name =" output_mrm_state" default =" /system/fail_safe/mrm_state" />
15
+ <arg name =" output_emergency_holding" default =" /system/emergency_holding" />
15
16
<arg name =" output_mrm_pull_over_operate" default =" /system/mrm/pull_over_manager/operate" />
16
17
<arg name =" output_mrm_comfortable_stop_operate" default =" /system/mrm/comfortable_stop/operate" />
17
18
<arg name =" output_mrm_emergency_stop_operate" default =" /system/mrm/emergency_stop/operate" />
32
33
<remap from =" ~/output/gear" to =" $(var output_gear)" />
33
34
<remap from =" ~/output/hazard" to =" $(var output_hazard)" />
34
35
<remap from =" ~/output/mrm/state" to =" $(var output_mrm_state)" />
36
+ <remap from =" ~/output/emergency_holding" to =" $(var output_emergency_holding)" />
35
37
<remap from =" ~/output/mrm/pull_over/operate" to =" $(var output_mrm_pull_over_operate)" />
36
38
<remap from =" ~/output/mrm/comfortable_stop/operate" to =" $(var output_mrm_comfortable_stop_operate)" />
37
39
<remap from =" ~/output/mrm/emergency_stop/operate" to =" $(var output_mrm_emergency_stop_operate)" />
Original file line number Diff line number Diff line change @@ -49,6 +49,8 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler"
49
49
create_publisher<autoware_vehicle_msgs::msg::GearCommand>(" ~/output/gear" , rclcpp::QoS{1 });
50
50
pub_mrm_state_ =
51
51
create_publisher<autoware_adapi_v1_msgs::msg::MrmState>(" ~/output/mrm/state" , rclcpp::QoS{1 });
52
+ pub_emergency_holding_ = create_publisher<tier4_system_msgs::msg::EmergencyHoldingState>(
53
+ " ~/output/emergency_holding" , rclcpp::QoS{1 });
52
54
53
55
// Clients
54
56
client_mrm_pull_over_group_ = create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -153,6 +155,14 @@ void MrmHandler::publishMrmState()
153
155
pub_mrm_state_->publish (mrm_state_);
154
156
}
155
157
158
+ void MrmHandler::publishEmergencyHolding ()
159
+ {
160
+ tier4_system_msgs::msg::EmergencyHoldingState msg;
161
+ msg.stamp = this ->now ();
162
+ msg.is_holding = is_emergency_holding_;
163
+ pub_emergency_holding_->publish (msg);
164
+ }
165
+
156
166
void MrmHandler::operateMrm ()
157
167
{
158
168
using autoware_adapi_v1_msgs::msg::MrmState;
@@ -352,6 +362,7 @@ void MrmHandler::onTimer()
352
362
publishMrmState ();
353
363
publishHazardCmd ();
354
364
publishGearCmd ();
365
+ publishEmergencyHolding ();
355
366
}
356
367
357
368
void MrmHandler::transitionTo (const int new_state)
You can’t perform that action at this time.
0 commit comments