Skip to content

Commit 09b5382

Browse files
add option to use emergency brake commands from vehicle_cmd_gate and not set emergency brake
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent e9e2832 commit 09b5382

File tree

3 files changed

+7
-1
lines changed

3 files changed

+7
-1
lines changed

pacmod_interface/config/pacmod.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
base_frame_id: "base_link"
44
command_timeout_ms: 1000
55
loop_rate: 30.0
6+
use_external_emergency_brake: false
67
emergency_brake: 0.7
78
max_throttle: 0.4
89
max_brake: 0.8

pacmod_interface/include/pacmod_interface/pacmod_interface.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -139,6 +139,7 @@ class PacmodInterface : public rclcpp::Node
139139
double brake_pedal_offset_; // offset of brake pedal value
140140

141141
double emergency_brake_; // brake command when emergency [m/s^2]
142+
bool use_external_emergency_brake_; // set to true to not use emergency_brake_
142143
double max_throttle_; // max throttle [0~1]
143144
double max_brake_; // max throttle [0~1]
144145
double max_steering_wheel_; // max steering wheel angle [rad]

pacmod_interface/src/pacmod_interface/pacmod_interface.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ PacmodInterface::PacmodInterface()
3737

3838
/* parameters for emergency stop */
3939
emergency_brake_ = declare_parameter("emergency_brake", 0.7);
40+
use_external_emergency_brake_ = declare_parameter("use_external_emergency_brake", false);
4041

4142
/* vehicle parameters */
4243
vgr_coef_a_ = declare_parameter("vgr_coef_a", 15.713);
@@ -411,7 +412,10 @@ void PacmodInterface::publishCommands()
411412
if (t_out >= 0 && (control_cmd_delta_time_ms > t_out || actuation_cmd_delta_time_ms > t_out)) {
412413
timeouted = true;
413414
}
414-
if (is_emergency_ || timeouted) {
415+
/* check emergency and timeout */
416+
const bool emergency_brake_needed =
417+
(is_emergency_ && !use_external_emergency_brake_) || timeouted;
418+
if (emergency_brake_needed) {
415419
RCLCPP_ERROR(
416420
get_logger(), "Emergency Stopping, emergency = %d, timeouted = %d", is_emergency_, timeouted);
417421
desired_throttle = 0.0;

0 commit comments

Comments
 (0)