Skip to content

Commit 5515d35

Browse files
refactor isFrontObstacle
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent 25651d6 commit 5515d35

File tree

1 file changed

+13
-13
lines changed
  • planning/obstacle_cruise_planner/src

1 file changed

+13
-13
lines changed

planning/obstacle_cruise_planner/src/node.cpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -54,14 +54,15 @@ std::optional<T> getObstacleFromUuid(
5454
return *itr;
5555
}
5656

57-
bool isFrontObstacle(
57+
std::optional<double> calcDistanceToFrontVehicle(
5858
const std::vector<TrajectoryPoint> & traj_points, const size_t ego_idx,
59-
const geometry_msgs::msg::Point & obstacle_pos, double * ego_to_obstacle_distance)
59+
const geometry_msgs::msg::Point & obstacle_pos)
6060
{
6161
const size_t obstacle_idx = motion_utils::findNearestIndex(traj_points, obstacle_pos);
62-
63-
*ego_to_obstacle_distance = motion_utils::calcSignedArcLength(traj_points, ego_idx, obstacle_idx);
64-
return *ego_to_obstacle_distance >= 0.0;
62+
const auto ego_to_obstacle_distance =
63+
motion_utils::calcSignedArcLength(traj_points, ego_idx, obstacle_idx);
64+
if (ego_to_obstacle_distance < 0.0) return std::nullopt;
65+
return ego_to_obstacle_distance;
6566
}
6667

6768
PredictedPath resampleHighestConfidencePredictedPath(
@@ -629,21 +630,20 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
629630

630631
// 2. Check if the obstacle is in front of the ego.
631632
const size_t ego_idx = ego_nearest_param_.findIndex(traj_points, ego_odom_ptr_->pose.pose);
632-
double ego_to_obstacle_distance;
633-
const bool is_front_obstacle = isFrontObstacle(
634-
traj_points, ego_idx, current_obstacle_pose.pose.position, &ego_to_obstacle_distance);
635-
if (!is_front_obstacle) {
633+
const auto ego_to_obstacle_distance =
634+
calcDistanceToFrontVehicle(traj_points, ego_idx, current_obstacle_pose.pose.position);
635+
if (!ego_to_obstacle_distance) {
636636
RCLCPP_INFO_EXPRESSION(
637637
get_logger(), enable_debug_info_, "Ignore obstacle (%s) since it is not front obstacle.",
638638
object_id.c_str());
639639
continue;
640640
}
641641

642642
// 3. Check if rough lateral distance is smaller than the threshold
643-
double lat_dist_from_obstacle_to_traj;
643+
double lat_dist_from_obstacle_to_traj =
644+
motion_utils::calcLateralOffset(traj_points, current_obstacle_pose.pose.position);
645+
644646
const double min_lat_dist_to_traj_poly = [&]() {
645-
lat_dist_from_obstacle_to_traj =
646-
motion_utils::calcLateralOffset(traj_points, current_obstacle_pose.pose.position);
647647
const double obstacle_max_length = calcObstacleMaxLength(predicted_object.shape);
648648
return std::abs(lat_dist_from_obstacle_to_traj) - vehicle_info_.vehicle_width_m -
649649
obstacle_max_length;
@@ -660,7 +660,7 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
660660
}
661661

662662
const auto target_obstacle = Obstacle(
663-
obj_stamp, predicted_object, current_obstacle_pose.pose, ego_to_obstacle_distance,
663+
obj_stamp, predicted_object, current_obstacle_pose.pose, ego_to_obstacle_distance.value(),
664664
lat_dist_from_obstacle_to_traj);
665665
target_obstacles.push_back(target_obstacle);
666666
}

0 commit comments

Comments
 (0)