34
34
receiver_board::receiver_board (ros::NodeHandle& n)
35
35
: pub_bumper{ n.advertise <std_msgs::ByteMultiArray>(" /sensor_set/bumper" , queue_size) }
36
36
, pub_emergency_switch{ n.advertise <std_msgs::Bool>(" /sensor_set/emergency_switch" , queue_size) }
37
- , pub_emergency_stop { n.advertise <std_msgs::Bool>(" /body_control/emergency_stop " , queue_size) }
37
+ , pub_emergency_state { n.advertise <std_msgs::Bool>(" /body_control/emergency_state " , queue_size) }
38
38
, pub_charge{ n.advertise <std_msgs::Byte >(" /body_control/charge_status" , queue_size) }
39
39
, pub_power{ n.advertise <std_msgs::Byte >(" /body_control/power_state" , queue_size) }
40
40
, pub_charge_delay{ n.advertise <std_msgs::UInt8 >(" /body_control/charge_heartbeat_delay" , queue_size) }
@@ -49,7 +49,7 @@ void receiver_board::handle(const can_frame& frame) const
49
49
return ;
50
50
publish_bumper (frame);
51
51
publish_emergency_switch (frame);
52
- publish_emergency_stop (frame);
52
+ publish_emergency_state (frame);
53
53
publish_charge (frame);
54
54
publish_power (frame);
55
55
publish_charge_delay (frame);
@@ -73,11 +73,11 @@ void receiver_board::publish_emergency_switch(const can_frame& frame) const
73
73
pub_emergency_switch.publish (msg);
74
74
}
75
75
76
- void receiver_board::publish_emergency_stop (const can_frame& frame) const
76
+ void receiver_board::publish_emergency_state (const can_frame& frame) const
77
77
{
78
78
std_msgs::Bool msg;
79
79
msg.data = (frame.data [0 ] & 0b00000100 ) != 0 ;
80
- pub_emergency_stop .publish (msg);
80
+ pub_emergency_state .publish (msg);
81
81
}
82
82
83
83
void receiver_board::publish_charge (const can_frame& frame) const
0 commit comments