Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(dynamic_obstacle_avoidace, side_shift, sampling_planner): use planning factor #1729

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface
{
return std::make_unique<DynamicObstacleAvoidanceModule>(
name_, *node_, parameters_, rtc_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_);
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_);
}

void updateModuleParams(const std::vector<rclcpp::Parameter> & parameters) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -351,7 +351,8 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
std::shared_ptr<DynamicAvoidanceParameters> parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
objects_of_interest_marker_interface_ptr_map);
objects_of_interest_marker_interface_ptr_map,
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface);

void updateModuleParams(const std::any & parameters) override
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -331,8 +331,9 @@ DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule(
std::shared_ptr<DynamicAvoidanceParameters> parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
objects_of_interest_marker_interface_ptr_map)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
objects_of_interest_marker_interface_ptr_map,
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT
parameters_{std::move(parameters)},
target_objects_manager_{TargetObjectsManager(
parameters_->successive_num_to_entry_dynamic_avoidance_condition,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class SamplingPlannerModuleManager : public SceneModuleManagerInterface
{
return std::make_unique<SamplingPlannerModule>(
name_, *node_, parameters_, rtc_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_);
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_);
}

void updateModuleParams(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,8 @@ class SamplingPlannerModule : public SceneModuleInterface
const std::shared_ptr<SamplingPlannerParameters> & parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
objects_of_interest_marker_interface_ptr_map);
objects_of_interest_marker_interface_ptr_map,
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface);

bool isExecutionRequested() const override;
bool isExecutionReady() const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,9 @@ SamplingPlannerModule::SamplingPlannerModule(
const std::shared_ptr<SamplingPlannerParameters> & parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
objects_of_interest_marker_interface_ptr_map)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
objects_of_interest_marker_interface_ptr_map,
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT
vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}
{
internal_params_ = std::make_shared<SamplingPlannerInternalParameters>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface
{
return std::make_unique<SideShiftModule>(
name_, *node_, parameters_, rtc_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_);
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_);
}

void updateModuleParams(const std::vector<rclcpp::Parameter> & parameters) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,8 @@ class SideShiftModule : public SceneModuleInterface
const std::shared_ptr<SideShiftParameters> & parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
objects_of_interest_marker_interface_ptr_map);
objects_of_interest_marker_interface_ptr_map,
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface);

bool isExecutionRequested() const override;
bool isExecutionReady() const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,9 @@ SideShiftModule::SideShiftModule(
const std::shared_ptr<SideShiftParameters> & parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
objects_of_interest_marker_interface_ptr_map)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
objects_of_interest_marker_interface_ptr_map,
const std::shared_ptr<PlanningFactorInterface> planning_factor_interface)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT
parameters_{parameters}
{
}
Expand Down
Loading