Skip to content

Commit bed6b8e

Browse files
committed
feat: add use control command gate (#140)
Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com>
1 parent 4dbe2ed commit bed6b8e

File tree

2 files changed

+8
-4
lines changed

2 files changed

+8
-4
lines changed

awapi_awiv_adapter/launch/awapi_awiv_adapter.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
<launch>
2+
<arg name="use_control_command_gate" default="false"/>
23
<arg name="adapter_output" default="screen"/>
34
<arg name="relay_output" default="log"/>
45
<arg name="status_pub_hz" default="5.0"/>
@@ -139,6 +140,7 @@
139140
<param name="status_pub_hz" value="$(var status_pub_hz)"/>
140141
<param name="stop_reason_timeout" value="$(var stop_reason_timeout)"/>
141142
<param name="stop_reason_thresh_dist" value="$(var stop_reason_thresh_dist)"/>
143+
<param name="use_control_command_gate" value="$(var use_control_command_gate)"/>
142144
</node>
143145
</group>
144146

awapi_awiv_adapter/src/awapi_awiv_adapter_core.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -31,10 +31,12 @@ AutowareIvAdapter::AutowareIvAdapter()
3131
stop_reason_thresh_dist_ = this->declare_parameter("stop_reason_thresh_dist", 100.0);
3232
const double default_max_velocity = waitForParam<double>(
3333
this, declare_parameter("node/max_velocity", ""), declare_parameter("param/max_velocity", ""));
34-
const bool em_stop_param = waitForParam<bool>(
35-
this, declare_parameter("node/emergency_stop", ""),
36-
declare_parameter("param/emergency_stop", ""));
37-
emergencyParamCheck(em_stop_param);
34+
if (!this->declare_parameter("use_control_command_gate", false)) {
35+
const bool em_stop_param = waitForParam<bool>(
36+
this, declare_parameter("node/emergency_stop", ""),
37+
declare_parameter("param/emergency_stop", ""));
38+
emergencyParamCheck(em_stop_param);
39+
}
3840

3941
// setup instance
4042
vehicle_state_publisher_ = std::make_unique<AutowareIvVehicleStatePublisher>(*this);

0 commit comments

Comments
 (0)