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 Feb 26, 2025
1 parent d12367c commit 04596a1
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,8 @@ bool set_goal(
* @param [in] goal original goal pose
* @param [in] goal_lanelet lanelet containing the goal pose
*/
const geometry_msgs::msg::Pose refine_goal(const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelet & goal_lanelet);
const geometry_msgs::msg::Pose refine_goal(
const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelet & goal_lanelet);

/**
* @brief Recreate the path with a given goal pose.
Expand Down Expand Up @@ -219,8 +220,7 @@ bool is_path_valid(
* @return Modified path
*/
PathWithLaneId modify_path_for_smooth_goal_connection(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data
);
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data);

} // namespace utils
} // namespace autoware::path_generator
Expand Down
22 changes: 10 additions & 12 deletions planning/autoware_path_generator/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,7 @@ std::optional<size_t> find_index_out_of_goal_search_range(
for (size_t i = 0; i < points.size(); ++i) {
const auto & lane_ids = points.at(i).lane_ids;

const double dist_to_goal =
autoware_utils::calc_distance2d(points.at(i).point.pose, goal);
const double dist_to_goal = autoware_utils::calc_distance2d(points.at(i).point.pose, goal);
const bool is_goal_lane_id_in_point =
std::find(lane_ids.begin(), lane_ids.end(), goal_lane_id) != lane_ids.end();

Check warning on line 104 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L104

Added line #L104 was not covered by tests
if (dist_to_goal < max_dist && dist_to_goal < min_dist && is_goal_lane_id_in_point) {
Expand Down Expand Up @@ -416,8 +415,8 @@ bool set_goal(
autoware_utils::calc_offset_pose(goal, goal_to_pre_goal_distance, 0.0, 0.0);

Check warning on line 415 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L415

Added line #L415 was not covered by tests
const size_t closest_seg_idx_for_pre_goal =
find_nearest_segment_index(input.points, pre_refined_goal.point.pose, 3.0, M_PI_4);
pre_refined_goal.point.pose.position.z =
calc_interpolated_z(input, pre_refined_goal.point.pose.position, closest_seg_idx_for_pre_goal);
pre_refined_goal.point.pose.position.z = calc_interpolated_z(

Check warning on line 418 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L417-L418

Added lines #L417 - L418 were not covered by tests
input, pre_refined_goal.point.pose.position, closest_seg_idx_for_pre_goal);
pre_refined_goal.point.longitudinal_velocity_mps =
calc_interpolated_velocity(input, closest_seg_idx_for_pre_goal);

Check warning on line 421 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L420-L421

Added lines #L420 - L421 were not covered by tests

Expand Down Expand Up @@ -466,7 +465,8 @@ bool set_goal(
}

Check warning on line 465 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L465

Added line #L465 was not covered by tests
}

const geometry_msgs::msg::Pose refine_goal(const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelet & goal_lanelet)
const geometry_msgs::msg::Pose refine_goal(

Check warning on line 468 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L468

Added line #L468 was not covered by tests
const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelet & goal_lanelet)
{
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(goal.position);

Check warning on line 471 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L471

Added line #L471 was not covered by tests
const double distance = boost::geometry::distance(
Expand Down Expand Up @@ -526,8 +526,7 @@ PathWithLaneId refine_path_for_goal(
}

Check warning on line 526 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L525-L526

Added lines #L525 - L526 were not covered by tests

lanelet::ConstLanelets extract_lanelets_from_path(

Check warning on line 528 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L528

Added line #L528 was not covered by tests
const PathWithLaneId & refined_path,
const std::shared_ptr<const PlannerData> & planner_data)
const PathWithLaneId & refined_path, const std::shared_ptr<const PlannerData> & planner_data)
{
lanelet::ConstLanelets refined_path_lanelets;
for (size_t i = 0; i < refined_path.points.size(); ++i) {
Expand Down Expand Up @@ -567,8 +566,7 @@ bool is_in_lanelets(const geometry_msgs::msg::Pose & pose, const lanelet::ConstL
}

bool is_path_valid(

Check warning on line 568 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L568

Added line #L568 was not covered by tests
const PathWithLaneId & refined_path,
const std::shared_ptr<const PlannerData> & planner_data)
const PathWithLaneId & refined_path, const std::shared_ptr<const PlannerData> & planner_data)
{
const auto lanelets = extract_lanelets_from_path(refined_path, planner_data);

Check warning on line 571 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L571

Added line #L571 was not covered by tests
// std::any_of detects whether any point lies outside lanelets
Expand All @@ -581,8 +579,7 @@ bool is_path_valid(
}

Check warning on line 579 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L578-L579

Added lines #L578 - L579 were not covered by tests

PathWithLaneId modify_path_for_smooth_goal_connection(

Check warning on line 581 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L581

Added line #L581 was not covered by tests
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data
)
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data)
{
const auto goal = planner_data->goal_pose;
const auto goal_lane_id = planner_data->goal_lane_id;

Check warning on line 585 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L584-L585

Added lines #L584 - L585 were not covered by tests
Expand All @@ -598,7 +595,8 @@ PathWithLaneId modify_path_for_smooth_goal_connection(
refined_goal = goal;

Check warning on line 595 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L595

Added line #L595 was not covered by tests
}
}
double goal_search_radius{planner_data->path_generator_parameters.refine_goal_search_radius_range};
double goal_search_radius{
planner_data->path_generator_parameters.refine_goal_search_radius_range};

Check warning on line 599 in planning/autoware_path_generator/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_path_generator/src/utils.cpp#L599

Added line #L599 was not covered by tests

// TODO(shen): define in the parameter
constexpr double range_reduce_by{1.0}; // set a reasonable value, 10% - 20% of the
Expand Down

0 comments on commit 04596a1

Please sign in to comment.