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(lane_change): use planning factor #1727

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 @@ -32,13 +32,15 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface(
const std::shared_ptr<AvoidanceByLCParameters> & avoidance_by_lane_change_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)
: LaneChangeInterface{
name,
node,
parameters,
rtc_interface_ptr_map,
objects_of_interest_marker_interface_ptr_map,
planning_factor_interface,
std::make_unique<AvoidanceByLaneChange>(parameters, avoidance_by_lane_change_parameters)}
{
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface
const std::shared_ptr<AvoidanceByLCParameters> & avoidance_by_lane_change_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;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ SMIPtr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance()
{
return std::make_unique<AvoidanceByLaneChangeInterface>(
name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_);
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_);
}

} // namespace autoware::behavior_path_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance()
{
return std::make_unique<LaneChangeInterface>(
name_, *node_, parameters_, rtc_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_,
std::make_unique<ExternalRequestLaneChange>(parameters_, direction_));
}

Expand All @@ -37,7 +37,7 @@ ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance()
{
return std::make_unique<LaneChangeInterface>(
name_, *node_, parameters_, rtc_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_,
std::make_unique<ExternalRequestLaneChange>(parameters_, direction_));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ class LaneChangeInterface : public SceneModuleInterface
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,
const std::shared_ptr<PlanningFactorInterface> & planning_factor_interface,
std::unique_ptr<LaneChangeBase> && module_type);

LaneChangeInterface(const LaneChangeInterface &) = delete;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,9 @@ LaneChangeInterface::LaneChangeInterface(
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,
const std::shared_ptr<PlanningFactorInterface> & planning_factor_interface,
std::unique_ptr<LaneChangeBase> && module_type)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT
parameters_{std::move(parameters)},
module_type_{std::move(module_type)},
prev_approved_path_{std::make_unique<PathWithLaneId>()}
Expand Down Expand Up @@ -150,6 +151,8 @@ BehaviorModuleOutput LaneChangeInterface::plan()
}
}

set_longitudinal_planning_factor(output.path);

setVelocityFactor(output.path);

return output;
Expand Down Expand Up @@ -188,6 +191,8 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
isExecutionReady(), State::WAITING_FOR_EXECUTION);
is_abort_path_approved_ = false;

set_longitudinal_planning_factor(out.path);

setVelocityFactor(out.path);

return out;
Expand Down Expand Up @@ -436,6 +441,20 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o
steering_factor_interface_.set(
{status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end},
{start_distance, finish_distance}, steering_factor_direction, SteeringFactor::TURNING, "");

const auto planning_factor_direction = std::invoke([&]() {
if (module_type_->getDirection() == Direction::LEFT) {
return PlanningFactor::SHIFT_LEFT;
}
if (module_type_->getDirection() == Direction::RIGHT) {
return PlanningFactor::SHIFT_RIGHT;
}
return PlanningFactor::UNKNOWN;
});

planning_factor_interface_->add(
start_distance, finish_distance, status.lane_change_path.info.shift_line.start,
status.lane_change_path.info.shift_line.end, planning_factor_direction, SafetyFactorArray{});
}

void LaneChangeInterface::updateSteeringFactorPtr(
Expand All @@ -452,5 +471,17 @@ void LaneChangeInterface::updateSteeringFactorPtr(
{selected_path.info.shift_line.start, selected_path.info.shift_line.end},
{output.start_distance_to_path_change, output.finish_distance_to_path_change},
steering_factor_direction, SteeringFactor::APPROACHING, "");

const uint16_t planning_factor_direction = std::invoke([&output]() {

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
const uint16_t planning_factor_direction = std::invoke([&output]() {
const auto planning_factor_direction = std::invoke([&output]() {

Just for code consistency purpose.

if (output.lateral_shift > 0.0) {
return PlanningFactor::SHIFT_LEFT;
}
return PlanningFactor::SHIFT_RIGHT;
});

planning_factor_interface_->add(
output.start_distance_to_path_change, output.finish_distance_to_path_change,
selected_path.info.shift_line.start, selected_path.info.shift_line.end,
planning_factor_direction, SafetyFactorArray{});
}
} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ std::unique_ptr<SceneModuleInterface> LaneChangeModuleManager::createNewSceneMod
{
return std::make_unique<LaneChangeInterface>(
name_, *node_, parameters_, rtc_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_,
objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_,
std::make_unique<NormalLaneChange>(parameters_, LaneChangeModuleType::NORMAL, direction_));
}

Expand Down
Loading