Skip to content

Commit

Permalink
feat(behavior_velocity_planner): enable auto mode without rtc_auto_mo…
Browse files Browse the repository at this point in the history
…de_manager (autowarefoundation#4054)

* temp

Signed-off-by: kyoichi-sugahara <[email protected]>

* define enbale_rtc param for crosswalk

Signed-off-by: kyoichi-sugahara <[email protected]>

* update

Signed-off-by: kyoichi-sugahara <[email protected]>

* update

Signed-off-by: kyoichi-sugahara <[email protected]>

* update

Signed-off-by: kyoichi-sugahara <[email protected]>

* add enable_rtc param

Signed-off-by: kyoichi-sugahara <[email protected]>

* modify enable_rtc param in intersection module

Signed-off-by: kyoichi-sugahara <[email protected]>

* change explanation

Signed-off-by: kyoichi-sugahara <[email protected]>

* fix typo

Signed-off-by: kyoichi-sugahara <[email protected]>

* update argument name of parameter

Signed-off-by: kyoichi-sugahara <[email protected]>

* fix typo

Signed-off-by: kyoichi-sugahara <[email protected]>

---------

Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara authored Jul 22, 2023
1 parent cbaaa69 commit 01cea10
Show file tree
Hide file tree
Showing 13 changed files with 34 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,3 +8,4 @@
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
adjacent_extend_width: 1.5 # [m]
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
4 changes: 3 additions & 1 deletion planning/behavior_velocity_blind_spot_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,9 @@
namespace behavior_velocity_planner
{
BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
planner_param_.use_pass_judge_line = node.declare_parameter<bool>(ns + ".use_pass_judge_line");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
common:
show_processing_time: false # [-] whether to show processing time
# param for input data
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
traffic_light_state_timeout: 3.0 # [s] timeout threshold for traffic light signal

# param for stop position
Expand Down
4 changes: 3 additions & 1 deletion planning/behavior_velocity_crosswalk_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,9 @@ namespace behavior_velocity_planner
using lanelet::autoware::Crosswalk;

CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
node.declare_parameter<bool>(std::string(getModuleName()) + ".common.enable_rtc"))
{
const std::string ns(getModuleName());

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,3 +8,4 @@
state_clear_time: 2.0
hold_stop_margin_distance: 0.0
distance_to_judge_over_stop_line: 0.5
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
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,9 @@ namespace behavior_velocity_planner
using lanelet::autoware::DetectionArea;

DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
planner_param_.stop_margin = node.declare_parameter<double>(ns + ".stop_margin");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,5 +48,9 @@
denoise_kernel: 1.0 # [m]
pub_debug_grid: false

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
intersection: true
intersection_to_occlusion: true

merge_from_private:
stop_duration_sec: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,13 @@
namespace behavior_velocity_planner
{
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(node, getModuleName()),
occlusion_rtc_interface_(&node, "intersection_occlusion")
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc.intersection")),
occlusion_rtc_interface_(
&node, "intersection_occlusion",
node.declare_parameter<bool>(
std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
{
const std::string ns(getModuleName());
auto & ip = intersection_param_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,3 +8,4 @@
stop_line_margin: 1.0 # [m] margin to auto-gen stop line at no stopping area
detection_area_length: 200.0 # [m] used to create detection area polygon
stuck_vehicle_front_margin: 6.0 # [m] obstacle stop max distance(5.0m)
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
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,9 @@ namespace behavior_velocity_planner
using lanelet::autoware::NoStoppingArea;

NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
auto & pp = planner_param_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -326,8 +326,9 @@ class SceneModuleManagerInterface
class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface
{
public:
SceneModuleManagerInterfaceWithRTC(rclcpp::Node & node, const char * module_name)
: SceneModuleManagerInterface(node, module_name), rtc_interface_(&node, module_name)
SceneModuleManagerInterfaceWithRTC(
rclcpp::Node & node, const char * module_name, const bool enable_rtc = true)
: SceneModuleManagerInterface(node, module_name), rtc_interface_(&node, module_name, enable_rtc)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,3 +5,4 @@
tl_state_timeout: 1.0
yellow_lamp_period: 2.75
enable_pass_judge: true
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
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,9 @@ namespace behavior_velocity_planner
using lanelet::TrafficLight;

TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
planner_param_.stop_margin = node.declare_parameter<double>(ns + ".stop_margin");
Expand Down

0 comments on commit 01cea10

Please sign in to comment.