Skip to content

Commit 5de2e4a

Browse files
authored
feat(behavior_velocity_detection_area): use base class without RTC (#9802)
* feat(behavior_velocity_detection_area): use base class without RTC Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent f211728 commit 5de2e4a

File tree

6 files changed

+15
-28
lines changed

6 files changed

+15
-28
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/config/detection_area.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -8,5 +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: false # 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
1211
suppress_pass_judge_when_stopping: false

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
1919

2020
<depend>autoware_behavior_velocity_planner_common</depend>
21-
<depend>autoware_behavior_velocity_rtc_interface</depend>
2221
<depend>autoware_lanelet2_extension</depend>
2322
<depend>autoware_motion_utils</depend>
2423
<depend>autoware_planning_msgs</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp

+5-11
Original file line numberDiff line numberDiff line change
@@ -34,8 +34,7 @@ using autoware::universe_utils::getOrDeclareParameter;
3434
using lanelet::autoware::DetectionArea;
3535

3636
DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
37-
: SceneModuleManagerInterfaceWithRTC(
38-
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
37+
: SceneModuleManagerInterface(node, getModuleName())
3938
{
4039
const std::string ns(DetectionAreaModuleManager::getModuleName());
4140
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
@@ -66,25 +65,20 @@ void DetectionAreaModuleManager::launchNewModules(
6665
registerModule(std::make_shared<DetectionAreaModule>(
6766
module_id, lane_id, *detection_area_with_lane_id.first, planner_param_,
6867
logger_.get_child("detection_area_module"), clock_));
69-
generateUUID(module_id);
70-
updateRTCStatus(
71-
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
72-
std::numeric_limits<double>::lowest(), path.header.stamp);
7368
}
7469
}
7570
}
7671

77-
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
72+
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
7873
DetectionAreaModuleManager::getModuleExpiredFunction(
7974
const tier4_planning_msgs::msg::PathWithLaneId & path)
8075
{
8176
const auto detection_area_id_set = planning_utils::getRegElemIdSetOnPath<DetectionArea>(
8277
path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose);
8378

84-
return
85-
[detection_area_id_set](const std::shared_ptr<SceneModuleInterfaceWithRTC> & scene_module) {
86-
return detection_area_id_set.count(scene_module->getModuleId()) == 0;
87-
};
79+
return [detection_area_id_set](const std::shared_ptr<SceneModuleInterface> & scene_module) {
80+
return detection_area_id_set.count(scene_module->getModuleId()) == 0;
81+
};
8882
}
8983

9084
} // namespace autoware::behavior_velocity_planner

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
#include <autoware/behavior_velocity_planner_common/plugin_interface.hpp>
2121
#include <autoware/behavior_velocity_planner_common/plugin_wrapper.hpp>
22-
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
22+
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
2323
#include <rclcpp/rclcpp.hpp>
2424

2525
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
@@ -29,7 +29,7 @@
2929

3030
namespace autoware::behavior_velocity_planner
3131
{
32-
class DetectionAreaModuleManager : public SceneModuleManagerInterfaceWithRTC
32+
class DetectionAreaModuleManager : public SceneModuleManagerInterface<>
3333
{
3434
public:
3535
explicit DetectionAreaModuleManager(rclcpp::Node & node);
@@ -41,8 +41,8 @@ class DetectionAreaModuleManager : public SceneModuleManagerInterfaceWithRTC
4141

4242
void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override;
4343

44-
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
45-
getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override;
44+
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)> getModuleExpiredFunction(
45+
const tier4_planning_msgs::msg::PathWithLaneId & path) override;
4646
};
4747

4848
class DetectionAreaModulePlugin : public PluginWrapper<DetectionAreaModuleManager>

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp

+4-9
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ DetectionAreaModule::DetectionAreaModule(
3737
const lanelet::autoware::DetectionArea & detection_area_reg_elem,
3838
const PlannerParam & planner_param, const rclcpp::Logger & logger,
3939
const rclcpp::Clock::SharedPtr clock)
40-
: SceneModuleInterfaceWithRTC(module_id, logger, clock),
40+
: SceneModuleInterface(module_id, logger, clock),
4141
lane_id_(lane_id),
4242
detection_area_reg_elem_(detection_area_reg_elem),
4343
state_(State::GO),
@@ -105,12 +105,10 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
105105
modified_stop_line_seg_idx = current_seg_idx;
106106
}
107107

108-
setDistance(stop_dist);
109-
110108
// Check state
111-
setSafe(detection_area::can_clear_stop_state(
112-
last_obstacle_found_time_, clock_->now(), planner_param_.state_clear_time));
113-
if (isActivated()) {
109+
const bool is_safe = detection_area::can_clear_stop_state(
110+
last_obstacle_found_time_, clock_->now(), planner_param_.state_clear_time);
111+
if (is_safe) {
114112
last_obstacle_found_time_ = {};
115113
if (!planner_param_.suppress_pass_judge_when_stopping || !is_stopped) {
116114
state_ = State::GO;
@@ -139,7 +137,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
139137
dead_line_seg_idx);
140138
if (dist_from_ego_to_dead_line < 0.0) {
141139
RCLCPP_WARN(logger_, "[detection_area] vehicle is over dead line");
142-
setSafe(true);
143140
return true;
144141
}
145142
}
@@ -152,7 +149,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
152149
if (
153150
state_ != State::STOP &&
154151
dist_from_ego_to_stop < -planner_param_.distance_to_judge_over_stop_line) {
155-
setSafe(true);
156152
return true;
157153
}
158154

@@ -169,7 +165,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
169165
RCLCPP_WARN_THROTTLE(
170166
logger_, *clock_, std::chrono::milliseconds(1000).count(),
171167
"[detection_area] vehicle is over stop border");
172-
setSafe(true);
173168
return true;
174169
}
175170
}

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,8 @@
2323

2424
#define EIGEN_MPL2_ONLY
2525
#include <Eigen/Core>
26+
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
2627
#include <autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
27-
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2828
#include <autoware_lanelet2_extension/regulatory_elements/detection_area.hpp>
2929
#include <rclcpp/rclcpp.hpp>
3030

@@ -38,7 +38,7 @@ using PathIndexWithPoint2d = std::pair<size_t, Point2d>; // front
3838
using PathIndexWithOffset = std::pair<size_t, double>; // front index, offset
3939
using tier4_planning_msgs::msg::PathWithLaneId;
4040

41-
class DetectionAreaModule : public SceneModuleInterfaceWithRTC
41+
class DetectionAreaModule : public SceneModuleInterface
4242
{
4343
public:
4444
enum class State { GO, STOP };

0 commit comments

Comments
 (0)