File tree 5 files changed +10
-12
lines changed
planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module
5 files changed +10
-12
lines changed Original file line number Diff line number Diff line change 18
18
<buildtool_depend >eigen3_cmake_module</buildtool_depend >
19
19
20
20
<depend >autoware_behavior_velocity_planner_common</depend >
21
- <depend >autoware_behavior_velocity_rtc_interface</depend >
22
21
<depend >autoware_lanelet2_extension</depend >
23
22
<depend >autoware_motion_utils</depend >
24
23
<depend >autoware_planning_msgs</depend >
Original file line number Diff line number Diff line change @@ -69,17 +69,16 @@ void DetectionAreaModuleManager::launchNewModules(
69
69
}
70
70
}
71
71
72
- std::function<bool (const std::shared_ptr<SceneModuleInterfaceWithRTC > &)>
72
+ std::function<bool (const std::shared_ptr<SceneModuleInterface > &)>
73
73
DetectionAreaModuleManager::getModuleExpiredFunction (
74
74
const tier4_planning_msgs::msg::PathWithLaneId & path)
75
75
{
76
76
const auto detection_area_id_set = planning_utils::getRegElemIdSetOnPath<DetectionArea>(
77
77
path, planner_data_->route_handler_ ->getLaneletMapPtr (), planner_data_->current_odometry ->pose );
78
78
79
- return
80
- [detection_area_id_set](const std::shared_ptr<SceneModuleInterfaceWithRTC> & scene_module) {
81
- return detection_area_id_set.count (scene_module->getModuleId ()) == 0 ;
82
- };
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
+ };
83
82
}
84
83
85
84
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change 19
19
20
20
#include < autoware/behavior_velocity_planner_common/plugin_interface.hpp>
21
21
#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>
23
23
#include < rclcpp/rclcpp.hpp>
24
24
25
25
#include < tier4_planning_msgs/msg/path_with_lane_id.hpp>
@@ -41,8 +41,8 @@ class DetectionAreaModuleManager : public SceneModuleManagerInterface<>
41
41
42
42
void launchNewModules (const tier4_planning_msgs::msg::PathWithLaneId & path) override ;
43
43
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 ;
46
46
};
47
47
48
48
class DetectionAreaModulePlugin : public PluginWrapper <DetectionAreaModuleManager>
Original file line number Diff line number Diff line change @@ -37,7 +37,7 @@ DetectionAreaModule::DetectionAreaModule(
37
37
const lanelet::autoware::DetectionArea & detection_area_reg_elem,
38
38
const PlannerParam & planner_param, const rclcpp::Logger & logger,
39
39
const rclcpp::Clock::SharedPtr clock)
40
- : SceneModuleInterfaceWithRTC (module_id, logger, clock),
40
+ : SceneModuleInterface (module_id, logger, clock),
41
41
lane_id_ (lane_id),
42
42
detection_area_reg_elem_(detection_area_reg_elem),
43
43
state_(State::GO),
Original file line number Diff line number Diff line change 23
23
24
24
#define EIGEN_MPL2_ONLY
25
25
#include < Eigen/Core>
26
+ #include < autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
26
27
#include < autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
27
- #include < autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
28
28
#include < autoware_lanelet2_extension/regulatory_elements/detection_area.hpp>
29
29
#include < rclcpp/rclcpp.hpp>
30
30
@@ -38,7 +38,7 @@ using PathIndexWithPoint2d = std::pair<size_t, Point2d>; // front
38
38
using PathIndexWithOffset = std::pair<size_t , double >; // front index, offset
39
39
using tier4_planning_msgs::msg::PathWithLaneId;
40
40
41
- class DetectionAreaModule : public SceneModuleInterfaceWithRTC
41
+ class DetectionAreaModule : public SceneModuleInterface
42
42
{
43
43
public:
44
44
enum class State { GO, STOP };
You can’t perform that action at this time.
0 commit comments