Skip to content

Commit

Permalink
fix(start_planner): use waypoints as centerline if available
Browse files Browse the repository at this point in the history
Signed-off-by: Mehmet Dogru <42mehmetdogru42@gmail.com>
  • Loading branch information
mehmetdogru committed Mar 6, 2025
1 parent 92da629 commit cdd08f8
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@ class StartPlannerModule : public SceneModuleInterface
bool receivedNewRoute() const;

bool isModuleRunning() const;
bool isCurrentPoseOnMiddleOfTheRoad() const;
bool isCurrentPoseOnCenterline() const;

/**
* @brief Check if the ego vehicle is preventing the rear vehicle from passing through.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -342,12 +342,12 @@ bool StartPlannerModule::isExecutionRequested() const
}

// Return false and do not request execution if any of the following conditions are true:
// - The start pose is on the middle of the road.
// - The start pose is on the centerline or on "waypoints" (custom centerline)
// - The vehicle has already arrived at the start position planner.
// - The vehicle has reached the goal position.
// - The vehicle is still moving.
if (
isCurrentPoseOnMiddleOfTheRoad() || isCloseToOriginalStartPose() || hasArrivedAtGoal() ||
isCurrentPoseOnCenterline() || isCloseToOriginalStartPose() || hasArrivedAtGoal() ||
isMoving()) {
return false;
}
Expand All @@ -367,12 +367,15 @@ bool StartPlannerModule::isModuleRunning() const
return getCurrentStatus() == ModuleStatus::RUNNING;
}

bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const
bool StartPlannerModule::isCurrentPoseOnCenterline() const
{
const auto & lanelet_map_ptr = planner_data_->route_handler->getLaneletMapPtr();
const Pose & current_pose = planner_data_->self_odometry->pose.pose;
const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_);
const double lateral_distance_to_center_lane =
lanelet::utils::getArcCoordinates(current_lanes, current_pose).distance;
lanelet::utils::getArcCoordinatesConsideringWaypoints(
current_lanes, current_pose, lanelet_map_ptr)
.distance;

return std::abs(lateral_distance_to_center_lane) < parameters_->th_distance_to_middle_of_the_road;
}
Expand Down

0 comments on commit cdd08f8

Please sign in to comment.