Skip to content

Commit

Permalink
fix after PR review
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <[email protected]>
  • Loading branch information
maxime-clem committed Jan 22, 2025
1 parent 675a38b commit 7f0660a
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,9 @@ Whether it is decided to slow down or stop is determined by the distance between
If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used.
If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used.

In addition, if parameter `action.use_map_stop_lines` is set to `true`, then the stop point may be moved to a stop line preceding the stop point where ego can confortably stop. Stop lines are defined in the vector map and must be attached to one of the lanelet followed by the ego trajectory.
In addition, if parameter `action.use_map_stop_lines` is set to `true`,
then the stop point may be moved to the earliest stop line preceding the stop point where ego can confortably stop.
Stop lines are defined in the vector map and must be attached to one of the lanelet followed by the ego trajectory.

![avoid_collision](./docs/ttcs_avoid.png)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ std::optional<geometry_msgs::msg::Pose> calculate_pose_ahead_of_collision(
std::optional<geometry_msgs::msg::Pose> calculate_last_in_lane_pose(
const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, PlannerParam params)
{
std::optional<geometry_msgs::msg::Pose> slowdown_pose;
std::optional<geometry_msgs::msg::Pose> last_in_lane_pose;

const auto outside_idx = point_to_avoid.trajectory_index;
const auto outside_arc_length =
Expand All @@ -108,20 +108,20 @@ std::optional<geometry_msgs::msg::Pose> calculate_last_in_lane_pose(
// then we use the base footprint (with distance buffers)
// finally, we use the raw footprint
for (const auto & ego_footprint : {expanded_footprint, base_footprint, raw_footprint}) {
slowdown_pose = calculate_last_avoiding_pose(
last_in_lane_pose = calculate_last_avoiding_pose(
ego_data.trajectory_points, ego_footprint, polygons_to_avoid, ego_data.min_stop_arc_length,
outside_arc_length, params.precision);
if (slowdown_pose) {
if (last_in_lane_pose) {
break;
}
}
// fallback to simply stopping ahead of the collision to avoid (regardless of being out of lane or
// not)
if (!slowdown_pose) {
slowdown_pose = calculate_pose_ahead_of_collision(
if (!last_in_lane_pose) {
last_in_lane_pose = calculate_pose_ahead_of_collision(
ego_data, point_to_avoid, expanded_footprint, params.precision);
}
return slowdown_pose;
return last_in_lane_pose;
}

std::optional<geometry_msgs::msg::Pose> calculate_slowdown_pose(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ struct PlannerData
autoware::vehicle_info_utils::VehicleInfo vehicle_info_;

/// @brief queries the traffic signal information of given Id. if keep_last_observation = true,
/// @details recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation
/// recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation
[[nodiscard]] std::optional<TrafficSignalStamped> get_traffic_signal(
const lanelet::Id id, const bool keep_last_observation = false) const;

Expand Down

0 comments on commit 7f0660a

Please sign in to comment.