Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Apr 9, 2024
1 parent 3c635f2 commit 42b7c5f
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,10 @@ namespace autoware
{
namespace behavior_path_planner
{
using ::behavior_path_planner::Direction;
using ::behavior_path_planner::LaneChangeInterface;
using ::behavior_path_planner::RTCInterface;
using ::behavior_path_planner::ObjectsOfInterestMarkerInterface;
using ::behavior_path_planner::Direction;
using ::behavior_path_planner::RTCInterface;

class AvoidanceByLaneChangeInterface : public LaneChangeInterface
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,13 @@ namespace autoware
{
namespace behavior_path_planner
{
using ::route_handler::Direction;
using ::behavior_path_planner::AvoidancePlanningData;
using ::behavior_path_planner::LaneChangeModuleManager;
using ::behavior_path_planner::LaneChangeModuleType;
using ::behavior_path_planner::SceneModuleInterface;
using ::behavior_path_planner::ObjectParameter;
using ::behavior_path_planner::SceneModuleInterface;
using ::behavior_path_planner::SceneModuleManagerInterface;
using ::route_handler::Direction;

class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,17 +25,17 @@ namespace autoware
{
namespace behavior_path_planner
{
using ::route_handler::Direction;
using ::behavior_path_planner::AvoidanceParameters;
using ::route_handler::Direction;
using AvoidanceDebugData = DebugData;
using ::behavior_path_planner::helper::avoidance::AvoidanceHelper;
using ::behavior_path_planner::LaneChangeParameters;
using ::behavior_path_planner::AvoidancePlanningData;
using ::behavior_path_planner::ObjectDataArray;
using ::behavior_path_planner::ObjectData;
using ::behavior_path_planner::PredictedObject;
using ::behavior_path_planner::LaneChangeModuleType;
using ::behavior_path_planner::LaneChangeParameters;
using ::behavior_path_planner::ObjectData;
using ::behavior_path_planner::ObjectDataArray;
using ::behavior_path_planner::Point2d;
using ::behavior_path_planner::PredictedObject;
using ::behavior_path_planner::helper::avoidance::AvoidanceHelper;

class AvoidanceByLaneChange : public ::behavior_path_planner::NormalLaneChange
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const
const auto & objects = avoidance_data_.target_objects;

const auto is_avoidance_target = [&p](const auto & object) {
const auto target_class = ::behavior_path_planner::utils::getHighestProbLabel(object.object.classification) == p.first;
const auto target_class = ::behavior_path_planner::utils::getHighestProbLabel(
object.object.classification) == p.first;
return target_class && object.avoid_required;
};

Expand Down Expand Up @@ -105,12 +106,14 @@ void AvoidanceByLaneChange::updateSpecialData()
if (avoidance_data_.target_objects.empty()) {
direction_ = Direction::NONE;
} else {
direction_ = ::behavior_path_planner::utils::avoidance::isOnRight(avoidance_data_.target_objects.front())
? Direction::LEFT
: Direction::RIGHT;
direction_ =
::behavior_path_planner::utils::avoidance::isOnRight(avoidance_data_.target_objects.front())
? Direction::LEFT
: Direction::RIGHT;
}

::behavior_path_planner::utils::avoidance::updateRegisteredObject(registered_objects_, avoidance_data_.target_objects, p);
::behavior_path_planner::utils::avoidance::updateRegisteredObject(
registered_objects_, avoidance_data_.target_objects, p);
::behavior_path_planner::utils::avoidance::compensateDetectionLost(
registered_objects_, avoidance_data_.target_objects, avoidance_data_.other_objects);

Expand All @@ -130,7 +133,8 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
data.reference_path_rough = prev_module_path_;

const auto resample_interval = avoidance_parameters_->resample_interval_for_planning;
data.reference_path = ::behavior_path_planner::utils::resamplePathWithSpline(data.reference_path_rough, resample_interval);
data.reference_path = ::behavior_path_planner::utils::resamplePathWithSpline(
data.reference_path_rough, resample_interval);

data.current_lanelets = getCurrentLanes();

Expand Down Expand Up @@ -237,11 +241,13 @@ std::optional<ObjectData> AvoidanceByLaneChange::createObjectData(

// Find the footprint point closest to the path, set to object_data.overhang_distance.
object_data.overhang_points =
::behavior_path_planner::utils::avoidance::calcEnvelopeOverhangDistance(object_data, data.reference_path);
::behavior_path_planner::utils::avoidance::calcEnvelopeOverhangDistance(
object_data, data.reference_path);

// Check whether the the ego should avoid the object.
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
::behavior_path_planner::utils::avoidance::fillAvoidanceNecessity(object_data, registered_objects_, vehicle_width, p);
::behavior_path_planner::utils::avoidance::fillAvoidanceNecessity(
object_data, registered_objects_, vehicle_width, p);

::behavior_path_planner::utils::avoidance::fillLongitudinalAndLengthByClosestEnvelopeFootprint(
data.reference_path_rough, getEgoPosition(), object_data);
Expand All @@ -251,7 +257,8 @@ std::optional<ObjectData> AvoidanceByLaneChange::createObjectData(
double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_object) const
{
const auto ego_width = getCommonParam().vehicle_width;
const auto nearest_object_type = ::behavior_path_planner::utils::getHighestProbLabel(nearest_object.object.classification);
const auto nearest_object_type =
::behavior_path_planner::utils::getHighestProbLabel(nearest_object.object.classification);
const auto nearest_object_parameter =
avoidance_parameters_->object_parameters.at(nearest_object_type);
const auto lateral_hard_margin = std::max(
Expand All @@ -262,7 +269,8 @@ double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_

avoidance_helper_->setData(planner_data_);
const auto shift_length = avoidance_helper_->getShiftLength(
nearest_object, ::behavior_path_planner::utils::avoidance::isOnRight(nearest_object), avoid_margin);
nearest_object, ::behavior_path_planner::utils::avoidance::isOnRight(nearest_object),
avoid_margin);

return avoidance_helper_->getMinAvoidanceDistance(shift_length);
}
Expand Down

0 comments on commit 42b7c5f

Please sign in to comment.