Skip to content

Commit

Permalink
feat(behavior_velocity_planner): add enable_all_modules_auto_mode arg…
Browse files Browse the repository at this point in the history
…ument 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]>
  • Loading branch information
kyoichi-sugahara authored and tkimura4 committed Jan 23, 2024
1 parent 0e0b12b commit 6ea6823
Show file tree
Hide file tree
Showing 8 changed files with 25 additions and 15 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
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 6ea6823

Please sign in to comment.