Skip to content

Commit

Permalink
Add enable_all_modules_auto_mode argument to launch files for behavio…
Browse files Browse the repository at this point in the history
…r_velocity_modules

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
  • Loading branch information
kyoichi-sugahara committed Jan 16, 2024
1 parent bffafcd commit da2e7f1
Show file tree
Hide file tree
Showing 7 changed files with 16 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -237,6 +237,7 @@
<param from="$(var behavior_velocity_smoother_type_param_path)"/>
<param from="$(var behavior_velocity_planner_common_param_path)"/>
<param name="launch_modules" value="$(var behavior_velocity_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<!-- <param from="$(var template_param_path)"/> -->
<param from="$(var behavior_velocity_planner_blind_spot_module_param_path)"/>
<param from="$(var behavior_velocity_planner_crosswalk_module_param_path)"/>
Expand Down
3 changes: 2 additions & 1 deletion planning/behavior_velocity_blind_spot_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
(!getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode") &&
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc")))
{
const std::string ns(getModuleName());
planner_param_.use_pass_judge_line =
Expand Down
3 changes: 2 additions & 1 deletion planning/behavior_velocity_crosswalk_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".common.enable_rtc"))
(!getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode") &&
getOrDeclareParameter<bool>(node, 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 @@ -36,7 +36,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
(!getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode") &&
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc")))
{
const std::string ns(getModuleName());
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,13 @@ using tier4_autoware_utils::getOrDeclareParameter;
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
(!getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode") &&
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc.intersection"))),
occlusion_rtc_interface_(
&node, "intersection_occlusion",
getOrDeclareParameter<bool>(
node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
(!getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode") &&
getOrDeclareParameter<bool>(
node, 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 @@ -36,7 +36,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
(!getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode") &&
getOrDeclareParameter<bool>(node, 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 @@ -32,7 +32,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
(!getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode") &&
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc")))
{
const std::string ns(getModuleName());
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
Expand Down

0 comments on commit da2e7f1

Please sign in to comment.