Skip to content

Commit 4ed851f

Browse files
takayuki5168soblin
andauthored
refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (#9799)
* split into planer_common and rtc_interface Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp Co-authored-by: Mamoru Sobue <mamoru.sobue@tier4.jp> * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp Co-authored-by: Mamoru Sobue <mamoru.sobue@tier4.jp> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Co-authored-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 231c341 commit 4ed851f

File tree

47 files changed

+562
-381
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

47 files changed

+562
-381
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp

+3-3
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_planner_common/scene_module_interface.hpp>
22+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2323
#include <rclcpp/rclcpp.hpp>
2424

2525
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
@@ -42,8 +42,8 @@ class BlindSpotModuleManager : public SceneModuleManagerInterfaceWithRTC
4242

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

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

4949
class BlindSpotModulePlugin : public PluginWrapper<BlindSpotModuleManager>

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@
1616
#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_
1717

1818
#include <autoware/behavior_velocity_blind_spot_module/util.hpp>
19-
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
2019
#include <autoware/behavior_velocity_planner_common/utilization/state_machine.hpp>
20+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2121
#include <rclcpp/rclcpp.hpp>
2222

2323
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
@@ -59,7 +59,7 @@ struct Safe
5959

6060
using BlindSpotDecision = std::variant<InternalError, OverPassJudge, Unsafe, Safe>;
6161

62-
class BlindSpotModule : public SceneModuleInterface
62+
class BlindSpotModule : public SceneModuleInterfaceWithRTC
6363
{
6464
public:
6565
struct DebugData

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml

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

2020
<depend>autoware_behavior_velocity_planner_common</depend>
21+
<depend>autoware_behavior_velocity_rtc_interface</depend>
2122
<depend>autoware_lanelet2_extension</depend>
2223
<depend>autoware_motion_utils</depend>
2324
<depend>autoware_perception_msgs</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ void BlindSpotModuleManager::launchNewModules(const tier4_planning_msgs::msg::Pa
8383
}
8484
}
8585

86-
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
86+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
8787
BlindSpotModuleManager::getModuleExpiredFunction(
8888
const tier4_planning_msgs::msg::PathWithLaneId & path)
8989
{

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ BlindSpotModule::BlindSpotModule(
4141
const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction,
4242
const std::shared_ptr<const PlannerData> planner_data, const PlannerParam & planner_param,
4343
const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock)
44-
: SceneModuleInterface(module_id, logger, clock),
44+
: SceneModuleInterfaceWithRTC(module_id, logger, clock),
4545
lane_id_(lane_id),
4646
planner_param_{planner_param},
4747
turn_direction_(turn_direction),

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
2323

2424
<depend>autoware_behavior_velocity_planner_common</depend>
25+
<depend>autoware_behavior_velocity_rtc_interface</depend>
2526
<depend>autoware_grid_map_utils</depend>
2627
<depend>autoware_internal_debug_msgs</depend>
2728
<depend>autoware_interpolation</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -216,7 +216,7 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path)
216216
}
217217
}
218218

219-
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
219+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
220220
CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path)
221221
{
222222
const auto rh = planner_data_->route_handler_;
@@ -233,7 +233,7 @@ CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path)
233233
crosswalk_id_set.insert(crosswalk.first->crosswalkLanelet().id());
234234
}
235235

236-
return [crosswalk_id_set](const std::shared_ptr<SceneModuleInterface> & scene_module) {
236+
return [crosswalk_id_set](const std::shared_ptr<SceneModuleInterfaceWithRTC> & scene_module) {
237237
return crosswalk_id_set.count(scene_module->getModuleId()) == 0;
238238
};
239239
}

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp

+3-3
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_planner_common/scene_module_interface.hpp>
22+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2323
#include <autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
2424
#include <rclcpp/rclcpp.hpp>
2525

@@ -48,8 +48,8 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC
4848

4949
void launchNewModules(const PathWithLaneId & path) override;
5050

51-
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)> getModuleExpiredFunction(
52-
const PathWithLaneId & path) override;
51+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
52+
getModuleExpiredFunction(const PathWithLaneId & path) override;
5353
};
5454

5555
class CrosswalkModulePlugin : public PluginWrapper<CrosswalkModuleManager>

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -176,7 +176,7 @@ CrosswalkModule::CrosswalkModule(
176176
const std::optional<int64_t> & reg_elem_id, const lanelet::LaneletMapPtr & lanelet_map_ptr,
177177
const PlannerParam & planner_param, const rclcpp::Logger & logger,
178178
const rclcpp::Clock::SharedPtr clock)
179-
: SceneModuleInterface(module_id, logger, clock),
179+
: SceneModuleInterfaceWithRTC(module_id, logger, clock),
180180
module_id_(module_id),
181181
planner_param_(planner_param),
182182
use_regulatory_element_(reg_elem_id)

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717

1818
#include "autoware/behavior_velocity_crosswalk_module/util.hpp"
1919

20-
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
20+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2121
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2222
#include <autoware/universe_utils/system/stop_watch.hpp>
2323
#include <autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
@@ -112,7 +112,7 @@ double InterpolateMap(
112112
}
113113
} // namespace
114114

115-
class CrosswalkModule : public SceneModuleInterface
115+
class CrosswalkModule : public SceneModuleInterfaceWithRTC
116116
{
117117
public:
118118
struct PlannerParam

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
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>
2122
<depend>autoware_lanelet2_extension</depend>
2223
<depend>autoware_motion_utils</depend>
2324
<depend>autoware_planning_msgs</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -74,16 +74,17 @@ void DetectionAreaModuleManager::launchNewModules(
7474
}
7575
}
7676

77-
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
77+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
7878
DetectionAreaModuleManager::getModuleExpiredFunction(
7979
const tier4_planning_msgs::msg::PathWithLaneId & path)
8080
{
8181
const auto detection_area_id_set = planning_utils::getRegElemIdSetOnPath<DetectionArea>(
8282
path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose);
8383

84-
return [detection_area_id_set](const std::shared_ptr<SceneModuleInterface> & scene_module) {
85-
return detection_area_id_set.count(scene_module->getModuleId()) == 0;
86-
};
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+
};
8788
}
8889

8990
} // namespace autoware::behavior_velocity_planner

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp

+3-3
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_planner_common/scene_module_interface.hpp>
22+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2323
#include <rclcpp/rclcpp.hpp>
2424

2525
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
@@ -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<SceneModuleInterface> &)> getModuleExpiredFunction(
45-
const tier4_planning_msgs::msg::PathWithLaneId & path) override;
44+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
45+
getModuleExpiredFunction(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

+1-1
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-
: SceneModuleInterface(module_id, logger, clock),
40+
: SceneModuleInterfaceWithRTC(module_id, logger, clock),
4141
lane_id_(lane_id),
4242
detection_area_reg_elem_(detection_area_reg_elem),
4343
state_(State::GO),

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>
2726
#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 SceneModuleInterface
41+
class DetectionAreaModule : public SceneModuleInterfaceWithRTC
4242
{
4343
public:
4444
enum class State { GO, STOP };

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
<buildtool_depend>autoware_cmake</buildtool_depend>
2121

2222
<depend>autoware_behavior_velocity_planner_common</depend>
23+
<depend>autoware_behavior_velocity_rtc_interface</depend>
2324
<depend>autoware_internal_debug_msgs</depend>
2425
<depend>autoware_interpolation</depend>
2526
<depend>autoware_lanelet2_extension</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -353,14 +353,14 @@ void IntersectionModuleManager::launchNewModules(
353353
}
354354
}
355355

356-
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
356+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
357357
IntersectionModuleManager::getModuleExpiredFunction(
358358
const tier4_planning_msgs::msg::PathWithLaneId & path)
359359
{
360360
const auto lane_set = planning_utils::getLaneletsOnPath(
361361
path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose);
362362

363-
return [lane_set](const std::shared_ptr<SceneModuleInterface> & scene_module) {
363+
return [lane_set](const std::shared_ptr<SceneModuleInterfaceWithRTC> & scene_module) {
364364
const auto intersection_module = std::dynamic_pointer_cast<IntersectionModule>(scene_module);
365365
const auto & associative_ids = intersection_module->getAssociativeIds();
366366
for (const auto & lane : lane_set) {

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <autoware/behavior_velocity_planner_common/plugin_interface.hpp>
2222
#include <autoware/behavior_velocity_planner_common/plugin_wrapper.hpp>
2323
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
24+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2425
#include <rclcpp/rclcpp.hpp>
2526

2627
#include <std_msgs/msg/string.hpp>
@@ -47,8 +48,8 @@ class IntersectionModuleManager : public SceneModuleManagerInterfaceWithRTC
4748

4849
void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override;
4950

50-
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)> getModuleExpiredFunction(
51-
const tier4_planning_msgs::msg::PathWithLaneId & path) override;
51+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
52+
getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override;
5253

5354
bool hasSameParentLaneletAndTurnDirectionWithRegistered(const lanelet::ConstLanelet & lane) const;
5455

@@ -63,7 +64,7 @@ class IntersectionModuleManager : public SceneModuleManagerInterfaceWithRTC
6364
tl_observation_pub_;
6465
};
6566

66-
class MergeFromPrivateModuleManager : public SceneModuleManagerInterface
67+
class MergeFromPrivateModuleManager : public SceneModuleManagerInterface<>
6768
{
6869
public:
6970
explicit MergeFromPrivateModuleManager(rclcpp::Node & node);

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ IntersectionModule::IntersectionModule(
5353
const PlannerParam & planner_param, const std::set<lanelet::Id> & associative_ids,
5454
const std::string & turn_direction, const bool has_traffic_light, rclcpp::Node & node,
5555
const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock)
56-
: SceneModuleInterface(module_id, logger, clock),
56+
: SceneModuleInterfaceWithRTC(module_id, logger, clock),
5757
planner_param_(planner_param),
5858
lane_id_(lane_id),
5959
associative_ids_(associative_ids),

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,8 @@
2222
#include "object_manager.hpp"
2323
#include "result.hpp"
2424

25-
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
2625
#include <autoware/behavior_velocity_planner_common/utilization/state_machine.hpp>
26+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2727
#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
2828
#include <rclcpp/rclcpp.hpp>
2929

@@ -46,7 +46,7 @@
4646
namespace autoware::behavior_velocity_planner
4747
{
4848

49-
class IntersectionModule : public SceneModuleInterface
49+
class IntersectionModule : public SceneModuleInterfaceWithRTC
5050
{
5151
public:
5252
struct PlannerParam

planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929

3030
namespace autoware::behavior_velocity_planner
3131
{
32-
class NoDrivableLaneModuleManager : public SceneModuleManagerInterface
32+
class NoDrivableLaneModuleManager : public SceneModuleManagerInterface<>
3333
{
3434
public:
3535
explicit NoDrivableLaneModuleManager(rclcpp::Node & node);

planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml

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

2020
<depend>autoware_behavior_velocity_planner_common</depend>
21+
<depend>autoware_behavior_velocity_rtc_interface</depend>
2122
<depend>autoware_interpolation</depend>
2223
<depend>autoware_lanelet2_extension</depend>
2324
<depend>autoware_motion_utils</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -69,16 +69,17 @@ void NoStoppingAreaModuleManager::launchNewModules(
6969
}
7070
}
7171

72-
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
72+
std::function<bool(const std::shared_ptr<SceneModuleInterfaceWithRTC> &)>
7373
NoStoppingAreaModuleManager::getModuleExpiredFunction(
7474
const tier4_planning_msgs::msg::PathWithLaneId & path)
7575
{
7676
const auto no_stopping_area_id_set = planning_utils::getRegElemIdSetOnPath<NoStoppingArea>(
7777
path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose);
7878

79-
return [no_stopping_area_id_set](const std::shared_ptr<SceneModuleInterface> & scene_module) {
80-
return no_stopping_area_id_set.count(scene_module->getModuleId()) == 0;
81-
};
79+
return
80+
[no_stopping_area_id_set](const std::shared_ptr<SceneModuleInterfaceWithRTC> & scene_module) {
81+
return no_stopping_area_id_set.count(scene_module->getModuleId()) == 0;
82+
};
8283
}
8384

8485
} // namespace autoware::behavior_velocity_planner

planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.hpp

+3-3
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_planner_common/scene_module_interface.hpp>
22+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2323
#include <rclcpp/rclcpp.hpp>
2424

2525
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
@@ -41,8 +41,8 @@ class NoStoppingAreaModuleManager : public SceneModuleManagerInterfaceWithRTC
4141

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

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

4848
class NoStoppingAreaModulePlugin : public PluginWrapper<NoStoppingAreaModuleManager>

planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ NoStoppingAreaModule::NoStoppingAreaModule(
4141
const lanelet::autoware::NoStoppingArea & no_stopping_area_reg_elem,
4242
const PlannerParam & planner_param, const rclcpp::Logger & logger,
4343
const rclcpp::Clock::SharedPtr clock)
44-
: SceneModuleInterface(module_id, logger, clock),
44+
: SceneModuleInterfaceWithRTC(module_id, logger, clock),
4545
lane_id_(lane_id),
4646
no_stopping_area_reg_elem_(no_stopping_area_reg_elem),
4747
planner_param_(planner_param),

planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@
1717

1818
#include "utils.hpp"
1919

20-
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
2120
#include <autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
2221
#include <autoware/behavior_velocity_planner_common/utilization/state_machine.hpp>
22+
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
2323
#include <autoware_lanelet2_extension/regulatory_elements/no_stopping_area.hpp>
2424
#include <rclcpp/rclcpp.hpp>
2525

@@ -31,7 +31,7 @@
3131

3232
namespace autoware::behavior_velocity_planner
3333
{
34-
class NoStoppingAreaModule : public SceneModuleInterface
34+
class NoStoppingAreaModule : public SceneModuleInterfaceWithRTC
3535
{
3636
public:
3737
struct PlannerParam

planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939

4040
namespace autoware::behavior_velocity_planner
4141
{
42-
class OcclusionSpotModuleManager : public SceneModuleManagerInterface
42+
class OcclusionSpotModuleManager : public SceneModuleManagerInterface<>
4343
{
4444
public:
4545
explicit OcclusionSpotModuleManager(rclcpp::Node & node);
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
# Behavior Velocity Planner Common
22

3-
This package provides common functions as a library, which are used in the `behavior_velocity_planner` node and modules.
3+
This package provides a behavior velocity interface without RTC, and common functions as a library, which are used in the `behavior_velocity_planner` node and modules.

0 commit comments

Comments
 (0)