Skip to content

Commit 7ff3085

Browse files
satoshi-otasoblin
authored andcommitted
feat(dynamic_obstacle_avoidace, side_shift, sampling_planner): use planning factor (#1729)
* feat(dynamic_obstacle_avoidance): use planning factor Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * feat(sampling_planner): use planning factor Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * feat(side_shift): use planning factor Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 9f02a13 commit 7ff3085

File tree

9 files changed

+18
-12
lines changed

9 files changed

+18
-12
lines changed

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface
4242
{
4343
return std::make_unique<DynamicObstacleAvoidanceModule>(
4444
name_, *node_, parameters_, rtc_interface_ptr_map_,
45-
objects_of_interest_marker_interface_ptr_map_);
45+
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_);
4646
}
4747

4848
void updateModuleParams(const std::vector<rclcpp::Parameter> & parameters) override;

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -351,7 +351,8 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
351351
std::shared_ptr<DynamicAvoidanceParameters> parameters,
352352
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
353353
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
354-
objects_of_interest_marker_interface_ptr_map);
354+
objects_of_interest_marker_interface_ptr_map,
355+
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface);
355356

356357
void updateModuleParams(const std::any & parameters) override
357358
{

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -331,8 +331,9 @@ DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule(
331331
std::shared_ptr<DynamicAvoidanceParameters> parameters,
332332
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
333333
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
334-
objects_of_interest_marker_interface_ptr_map)
335-
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
334+
objects_of_interest_marker_interface_ptr_map,
335+
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface)
336+
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT
336337
parameters_{std::move(parameters)},
337338
target_objects_manager_{TargetObjectsManager(
338339
parameters_->successive_num_to_entry_dynamic_avoidance_condition,

planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ class SamplingPlannerModuleManager : public SceneModuleManagerInterface
3838
{
3939
return std::make_unique<SamplingPlannerModule>(
4040
name_, *node_, parameters_, rtc_interface_ptr_map_,
41-
objects_of_interest_marker_interface_ptr_map_);
41+
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_);
4242
}
4343

4444
void updateModuleParams(

planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,8 @@ class SamplingPlannerModule : public SceneModuleInterface
8686
const std::shared_ptr<SamplingPlannerParameters> & parameters,
8787
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
8888
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
89-
objects_of_interest_marker_interface_ptr_map);
89+
objects_of_interest_marker_interface_ptr_map,
90+
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface);
9091

9192
bool isExecutionRequested() const override;
9293
bool isExecutionReady() const override;

planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,9 @@ SamplingPlannerModule::SamplingPlannerModule(
4242
const std::shared_ptr<SamplingPlannerParameters> & parameters,
4343
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
4444
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
45-
objects_of_interest_marker_interface_ptr_map)
46-
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
45+
objects_of_interest_marker_interface_ptr_map,
46+
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface)
47+
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT
4748
vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}
4849
{
4950
internal_params_ = std::make_shared<SamplingPlannerInternalParameters>();

planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface
3939
{
4040
return std::make_unique<SideShiftModule>(
4141
name_, *node_, parameters_, rtc_interface_ptr_map_,
42-
objects_of_interest_marker_interface_ptr_map_);
42+
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_);
4343
}
4444

4545
void updateModuleParams(const std::vector<rclcpp::Parameter> & parameters) override;

planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,8 @@ class SideShiftModule : public SceneModuleInterface
4545
const std::shared_ptr<SideShiftParameters> & parameters,
4646
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
4747
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
48-
objects_of_interest_marker_interface_ptr_map);
48+
objects_of_interest_marker_interface_ptr_map,
49+
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface);
4950

5051
bool isExecutionRequested() const override;
5152
bool isExecutionReady() const override;

planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,9 @@ SideShiftModule::SideShiftModule(
4242
const std::shared_ptr<SideShiftParameters> & parameters,
4343
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
4444
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
45-
objects_of_interest_marker_interface_ptr_map)
46-
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
45+
objects_of_interest_marker_interface_ptr_map,
46+
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface)
47+
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT
4748
parameters_{parameters}
4849
{
4950
}

0 commit comments

Comments
 (0)