Skip to content

Commit 30cd40e

Browse files
authored
Merge pull request #20 from LexxPluss/AMRSW-1112-fix-actuator-init-issue
AMRSW-1112 publish emergency_state
2 parents fc93d08 + c671da4 commit 30cd40e

File tree

2 files changed

+6
-6
lines changed

2 files changed

+6
-6
lines changed

src/receiver_board.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
receiver_board::receiver_board(ros::NodeHandle& n)
3535
: pub_bumper{ n.advertise<std_msgs::ByteMultiArray>("/sensor_set/bumper", queue_size) }
3636
, 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) }
3838
, pub_charge{ n.advertise<std_msgs::Byte>("/body_control/charge_status", queue_size) }
3939
, pub_power{ n.advertise<std_msgs::Byte>("/body_control/power_state", queue_size) }
4040
, 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
4949
return;
5050
publish_bumper(frame);
5151
publish_emergency_switch(frame);
52-
publish_emergency_stop(frame);
52+
publish_emergency_state(frame);
5353
publish_charge(frame);
5454
publish_power(frame);
5555
publish_charge_delay(frame);
@@ -73,11 +73,11 @@ void receiver_board::publish_emergency_switch(const can_frame& frame) const
7373
pub_emergency_switch.publish(msg);
7474
}
7575

76-
void receiver_board::publish_emergency_stop(const can_frame& frame) const
76+
void receiver_board::publish_emergency_state(const can_frame& frame) const
7777
{
7878
std_msgs::Bool msg;
7979
msg.data = (frame.data[0] & 0b00000100) != 0;
80-
pub_emergency_stop.publish(msg);
80+
pub_emergency_state.publish(msg);
8181
}
8282

8383
void receiver_board::publish_charge(const can_frame& frame) const

src/receiver_board.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -38,13 +38,13 @@ class receiver_board
3838
private:
3939
void publish_bumper(const can_frame& frame) const;
4040
void publish_emergency_switch(const can_frame& frame) const;
41-
void publish_emergency_stop(const can_frame& frame) const;
41+
void publish_emergency_state(const can_frame& frame) const;
4242
void publish_charge(const can_frame& frame) const;
4343
void publish_power(const can_frame& frame) const;
4444
void publish_charge_delay(const can_frame& frame) const;
4545
void publish_charge_voltage(const can_frame& frame) const;
4646
void publish_safety_lidar(const can_frame& frame) const;
47-
ros::Publisher pub_bumper, pub_emergency_switch, pub_emergency_stop, pub_charge, pub_power, pub_charge_delay,
47+
ros::Publisher pub_bumper, pub_emergency_switch, pub_emergency_state, pub_charge, pub_power, pub_charge_delay,
4848
pub_charge_voltage, pub_safety_lidar;
4949
static constexpr uint32_t queue_size{ 10 };
5050
};

0 commit comments

Comments
 (0)