Skip to content

Commit

Permalink
Merge pull request #1112 from tier4/feat/add_enable_all_auto_mode
Browse files Browse the repository at this point in the history
* feat(behavior_path_planner): add enable_all_modules_auto_mode argument to launch files for behavior path planner modules (autowarefoundation#6093)

* Add enable_all_modules_auto_mode argument to launch files

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

* set default value for enable_all_modules_auto_mode

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

* fix enable_rtc configuration in scene_module_manager_interface.hpp

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

---------

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

* feat(behavior_velocity_planner): add enable_all_modules_auto_mode argument to launch files for behavior velocity planner modules (autowarefoundation#6094)

* set default value for enable_all_modules_auto_mode

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

* fix enable_rtc configuration in scene_module_manager_interface.hpp

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

* Refactor scene module managers to use getEnableRTC function

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

---------

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

---------

Signed-off-by: kyoichi-sugahara <[email protected]>
Co-authored-by: Kyoichi Sugahara <[email protected]>
  • Loading branch information
tkimura4 and kyoichi-sugahara authored Jan 23, 2024
2 parents dc169fc + 6ea6823 commit 085dfca
Show file tree
Hide file tree
Showing 12 changed files with 47 additions and 18 deletions.
6 changes: 5 additions & 1 deletion launch/tier4_planning_launch/launch/planning.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
<arg name="freespace_planner_param_path"/>
<!-- planning validator -->
<arg name="planning_validator_param_path"/>
<!-- Auto mode setting-->
<arg name="enable_all_modules_auto_mode"/>

<group>
<push-ros-namespace namespace="planning"/>
Expand All @@ -21,7 +23,9 @@
<!-- scenario planning module -->
<group>
<push-ros-namespace namespace="scenario_planning"/>
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/scenario_planning.launch.xml"/>
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/scenario_planning.launch.xml">
<arg name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
</include>
</group>

<!-- planning validator -->
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
<launch>
<arg name="enable_all_modules_auto_mode"/>

<!-- lane_driving scenario -->
<group>
<push-ros-namespace namespace="lane_driving"/>
Expand All @@ -8,6 +10,7 @@
<group>
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml">
<arg name="container_type" value="component_container_mt"/>
<arg name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<!-- This condition should be true if run_out module is enabled and its detection method is Points -->
<arg name="launch_compare_map_pipeline" value="false"/>
</include>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<arg name="input_virtual_traffic_light_topic_name" default="/awapi/tmp/virtual_traffic_light_states"/>
<arg name="input_vector_map_topic_name" default="/map/vector_map"/>
<arg name="input_pointcloud_map_topic_name" default="/map/pointcloud_map"/>
<arg name="enable_all_modules_auto_mode"/>

<arg name="launch_avoidance_module" default="true"/>
<arg name="launch_avoidance_by_lane_change_module" default="true"/>
Expand Down Expand Up @@ -195,6 +196,7 @@
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param name="launch_modules" value="$(var behavior_path_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<param from="$(var behavior_path_planner_side_shift_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_by_lc_module_param_path)"/>
Expand Down Expand Up @@ -235,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
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
<launch>
<arg name="enable_all_modules_auto_mode"/>
<!-- scenario selector -->
<group>
<include file="$(find-pkg-share scenario_selector)/launch/scenario_selector.launch.xml">
Expand Down Expand Up @@ -50,7 +51,9 @@
<group>
<!-- lane driving -->
<group>
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/lane_driving.launch.xml"/>
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/lane_driving.launch.xml">
<arg name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
</include>
</group>
<!-- parking -->
<group>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -268,7 +268,14 @@ class SceneModuleManagerInterface
// init manager configuration
{
std::string ns = name_ + ".";
config_.enable_rtc = getOrDeclareParameter<bool>(*node, ns + "enable_rtc");
try {
config_.enable_rtc = getOrDeclareParameter<bool>(*node, "enable_all_modules_auto_mode")
? false
: getOrDeclareParameter<bool>(*node, ns + "enable_rtc");
} catch (const std::exception & e) {
config_.enable_rtc = getOrDeclareParameter<bool>(*node, ns + "enable_rtc");
}

config_.enable_simultaneous_execution_as_approved_module =
getOrDeclareParameter<bool>(*node, ns + "enable_simultaneous_execution_as_approved_module");
config_.enable_simultaneous_execution_as_candidate_module = getOrDeclareParameter<bool>(
Expand Down
5 changes: 1 addition & 4 deletions planning/behavior_velocity_blind_spot_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@

#include <behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <tier4_autoware_utils/ros/parameter.hpp>

#include <lanelet2_core/primitives/BasicRegulatoryElements.h>

Expand All @@ -28,12 +27,10 @@

namespace behavior_velocity_planner
{
using tier4_autoware_utils::getOrDeclareParameter;

BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
planner_param_.use_pass_judge_line =
Expand Down
3 changes: 1 addition & 2 deletions planning/behavior_velocity_crosswalk_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@ using tier4_autoware_utils::getOrDeclareParameter;

CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".common.enable_rtc"))
node, getModuleName(), getEnableRTC(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 @@ -35,8 +35,7 @@ using tier4_autoware_utils::getOrDeclareParameter;

DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
node, getModuleName(), getEnableRTC(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,10 @@ using tier4_autoware_utils::getOrDeclareParameter;
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
occlusion_rtc_interface_(
&node, "intersection_occlusion",
getOrDeclareParameter<bool>(
node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
getEnableRTC(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 @@ -35,8 +35,7 @@ using tier4_autoware_utils::getOrDeclareParameter;

NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
node, getModuleName(), getEnableRTC(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 @@ -22,6 +22,7 @@
#include <objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp>
#include <rtc_interface/rtc_interface.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/ros/parameter.hpp>

#include <autoware_adapi_v1_msgs/msg/velocity_factor.hpp>
#include <autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
Expand Down Expand Up @@ -52,6 +53,7 @@ using objects_of_interest_marker_interface::ColorName;
using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface;
using rtc_interface::RTCInterface;
using tier4_autoware_utils::DebugPublisher;
using tier4_autoware_utils::getOrDeclareParameter;
using tier4_debug_msgs::msg::Float64Stamped;
using tier4_planning_msgs::msg::StopFactor;
using tier4_planning_msgs::msg::StopReason;
Expand Down Expand Up @@ -251,6 +253,21 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface
void publishObjectsOfInterestMarker();

void deleteExpiredModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override;

bool getEnableRTC(rclcpp::Node & node, const std::string & param_name)
{
bool enable_rtc = true;

try {
enable_rtc = getOrDeclareParameter<bool>(node, "enable_all_modules_auto_mode")
? false
: getOrDeclareParameter<bool>(node, param_name);
} catch (const std::exception & e) {
enable_rtc = getOrDeclareParameter<bool>(node, param_name);
}

return enable_rtc;
}
};

} // namespace behavior_velocity_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@ using tier4_autoware_utils::getOrDeclareParameter;

TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
node, getModuleName(), getEnableRTC(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 085dfca

Please sign in to comment.