Skip to content

Commit 01cea10

Browse files
feat(behavior_velocity_planner): enable auto mode without rtc_auto_mode_manager (#4054)
* temp Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * define enbale_rtc param for crosswalk Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * update Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * update Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * update Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * add enable_rtc param Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * modify enable_rtc param in intersection module Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * change explanation Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix typo Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * update argument name of parameter Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix typo Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> --------- Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent cbaaa69 commit 01cea10

File tree

13 files changed

+34
-9
lines changed

13 files changed

+34
-9
lines changed

planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -8,3 +8,4 @@
88
max_future_movement_time: 10.0 # [second]
99
threshold_yaw_diff: 0.523 # [rad]
1010
adjacent_extend_width: 1.5 # [m]
11+
enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval

planning/behavior_velocity_blind_spot_module/src/manager.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,9 @@
2828
namespace behavior_velocity_planner
2929
{
3030
BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
31-
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
31+
: SceneModuleManagerInterfaceWithRTC(
32+
node, getModuleName(),
33+
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
3234
{
3335
const std::string ns(getModuleName());
3436
planner_param_.use_pass_judge_line = node.declare_parameter<bool>(ns + ".use_pass_judge_line");

planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
common:
55
show_processing_time: false # [-] whether to show processing time
66
# param for input data
7+
enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
78
traffic_light_state_timeout: 3.0 # [s] timeout threshold for traffic light signal
89

910
# param for stop position

planning/behavior_velocity_crosswalk_module/src/manager.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,9 @@ namespace behavior_velocity_planner
2828
using lanelet::autoware::Crosswalk;
2929

3030
CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
31-
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
31+
: SceneModuleManagerInterfaceWithRTC(
32+
node, getModuleName(),
33+
node.declare_parameter<bool>(std::string(getModuleName()) + ".common.enable_rtc"))
3234
{
3335
const std::string ns(getModuleName());
3436

planning/behavior_velocity_detection_area_module/config/detection_area.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -8,3 +8,4 @@
88
state_clear_time: 2.0
99
hold_stop_margin_distance: 0.0
1010
distance_to_judge_over_stop_line: 0.5
11+
enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval

planning/behavior_velocity_detection_area_module/src/manager.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,9 @@ namespace behavior_velocity_planner
3131
using lanelet::autoware::DetectionArea;
3232

3333
DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
34-
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
34+
: SceneModuleManagerInterfaceWithRTC(
35+
node, getModuleName(),
36+
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
3537
{
3638
const std::string ns(getModuleName());
3739
planner_param_.stop_margin = node.declare_parameter<double>(ns + ".stop_margin");

planning/behavior_velocity_intersection_module/config/intersection.param.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -48,5 +48,9 @@
4848
denoise_kernel: 1.0 # [m]
4949
pub_debug_grid: false
5050

51+
enable_rtc: # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
52+
intersection: true
53+
intersection_to_occlusion: true
54+
5155
merge_from_private:
5256
stop_duration_sec: 1.0

planning/behavior_velocity_intersection_module/src/manager.cpp

+7-2
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,13 @@
3030
namespace behavior_velocity_planner
3131
{
3232
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
33-
: SceneModuleManagerInterfaceWithRTC(node, getModuleName()),
34-
occlusion_rtc_interface_(&node, "intersection_occlusion")
33+
: SceneModuleManagerInterfaceWithRTC(
34+
node, getModuleName(),
35+
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc.intersection")),
36+
occlusion_rtc_interface_(
37+
&node, "intersection_occlusion",
38+
node.declare_parameter<bool>(
39+
std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
3540
{
3641
const std::string ns(getModuleName());
3742
auto & ip = intersection_param_;

planning/behavior_velocity_no_stopping_area_module/config/no_stopping_area.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -8,3 +8,4 @@
88
stop_line_margin: 1.0 # [m] margin to auto-gen stop line at no stopping area
99
detection_area_length: 200.0 # [m] used to create detection area polygon
1010
stuck_vehicle_front_margin: 6.0 # [m] obstacle stop max distance(5.0m)
11+
enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval

planning/behavior_velocity_no_stopping_area_module/src/manager.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,9 @@ namespace behavior_velocity_planner
3131
using lanelet::autoware::NoStoppingArea;
3232

3333
NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node)
34-
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
34+
: SceneModuleManagerInterfaceWithRTC(
35+
node, getModuleName(),
36+
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
3537
{
3638
const std::string ns(getModuleName());
3739
auto & pp = planner_param_;

planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -326,8 +326,9 @@ class SceneModuleManagerInterface
326326
class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface
327327
{
328328
public:
329-
SceneModuleManagerInterfaceWithRTC(rclcpp::Node & node, const char * module_name)
330-
: SceneModuleManagerInterface(node, module_name), rtc_interface_(&node, module_name)
329+
SceneModuleManagerInterfaceWithRTC(
330+
rclcpp::Node & node, const char * module_name, const bool enable_rtc = true)
331+
: SceneModuleManagerInterface(node, module_name), rtc_interface_(&node, module_name, enable_rtc)
331332
{
332333
}
333334

planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -5,3 +5,4 @@
55
tl_state_timeout: 1.0
66
yellow_lamp_period: 2.75
77
enable_pass_judge: true
8+
enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval

planning/behavior_velocity_traffic_light_module/src/manager.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,9 @@ namespace behavior_velocity_planner
2828
using lanelet::TrafficLight;
2929

3030
TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
31-
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
31+
: SceneModuleManagerInterfaceWithRTC(
32+
node, getModuleName(),
33+
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
3234
{
3335
const std::string ns(getModuleName());
3436
planner_param_.stop_margin = node.declare_parameter<double>(ns + ".stop_margin");

0 commit comments

Comments
 (0)