Skip to content

Commit d77c48b

Browse files
pre-commit-ci[bot]shmpwk
authored andcommitted
style(pre-commit): autofix
1 parent 166b871 commit d77c48b

File tree

2 files changed

+9
-5
lines changed
  • common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path
  • planning/behavior_path_planner_common/src/utils/drivable_area_expansion

2 files changed

+9
-5
lines changed

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -82,9 +82,9 @@ void visualizeBound(
8282
}
8383
const float adjusted_width = width / std::sin(diff_angle);
8484
if (std::abs(adjusted_width) > 1.0) {
85-
return std::make_pair(normal_vector_angle, adjusted_width / std::abs(adjusted_width));
85+
return std::make_pair(normal_vector_angle, adjusted_width / std::abs(adjusted_width));
8686
} else {
87-
return std::make_pair(normal_vector_angle, adjusted_width);
87+
return std::make_pair(normal_vector_angle, adjusted_width);
8888
}
8989
}();
9090

planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -1582,15 +1582,19 @@ std::vector<geometry_msgs::msg::Point> postProcess(
15821582
calcLongitudinalOffsetGoalPoint(tmp_bound, goal_pose, goal_start_idx, vehicle_length);
15831583
const auto p_tmp =
15841584
geometry_msgs::build<Pose>().position(goal_point).orientation(goal_pose.orientation);
1585-
const size_t goal_nearest_idx = findNearestSegmentIndexFromLateralDistance(tmp_bound, p_tmp, M_PI_2);
1586-
const size_t goal_idx = ((goal_start_idx - start_idx)*(goal_start_idx - start_idx) > (goal_nearest_idx - start_idx)*(goal_nearest_idx - start_idx)) ? goal_start_idx : goal_nearest_idx;
1585+
const size_t goal_nearest_idx =
1586+
findNearestSegmentIndexFromLateralDistance(tmp_bound, p_tmp, M_PI_2);
1587+
const size_t goal_idx = ((goal_start_idx - start_idx) * (goal_start_idx - start_idx) >
1588+
(goal_nearest_idx - start_idx) * (goal_nearest_idx - start_idx))
1589+
? goal_start_idx
1590+
: goal_nearest_idx;
15871591
return std::make_pair(goal_idx, goal_point);
15881592
}();
15891593

15901594
// Insert middle points
15911595
size_t step = (start_idx < goal_idx) ? 1 : -1;
15921596
for (size_t i = start_idx + step; i != goal_idx + step; i += step) {
1593-
const auto &next_point = tmp_bound.at(i);
1597+
const auto & next_point = tmp_bound.at(i);
15941598
const double dist = tier4_autoware_utils::calcDistance2d(processed_bound.back(), next_point);
15951599
if (dist > overlap_threshold) {
15961600
processed_bound.push_back(next_point);

0 commit comments

Comments
 (0)