Skip to content

Commit 5bcd590

Browse files
danielsanchezaransaka1-s
authored andcommitted
feat(start_planner): add general turn signal method to start planner (autowarefoundation#6628)
* Add general turnSignal method to start planner Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * add description to ignore signal Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent 47bcea4 commit 5bcd590

File tree

2 files changed

+58
-90
lines changed

2 files changed

+58
-90
lines changed

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333

3434
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
3535

36+
#include <lanelet2_core/Forward.h>
3637
#include <tf2/utils.h>
3738

3839
#include <deque>
@@ -196,6 +197,10 @@ class StartPlannerModule : public SceneModuleInterface
196197
PullOutStatus status_;
197198
mutable StartGoalPlannerData start_planner_data_;
198199

200+
// Keeps track of lanelets that should be ignored when calculating the turnSignalInfo for this
201+
// module's output. If the ego vehicle is in this lanelet, the calculation is skipped.
202+
std::optional<lanelet::Id> ignore_signal_{std::nullopt};
203+
199204
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> odometry_buffer_;
200205

201206
std::unique_ptr<rclcpp::Time> last_route_received_time_;
@@ -218,7 +223,7 @@ class StartPlannerModule : public SceneModuleInterface
218223
std::shared_ptr<LaneDepartureChecker> lane_departure_checker_;
219224

220225
// turn signal
221-
TurnSignalInfo calcTurnSignalInfo() const;
226+
TurnSignalInfo calcTurnSignalInfo();
222227

223228
void incrementPathIndex();
224229
PathWithLaneId getCurrentPath() const;

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+52-89
Original file line numberDiff line numberDiff line change
@@ -1008,107 +1008,70 @@ bool StartPlannerModule::hasFinishedCurrentPath()
10081008
return is_near_target && isStopped();
10091009
}
10101010

1011-
TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() const
1011+
TurnSignalInfo StartPlannerModule::calcTurnSignalInfo()
10121012
{
1013-
TurnSignalInfo turn_signal{}; // output
1013+
const auto path = getFullPath();
1014+
if (path.points.empty()) return getPreviousModuleOutput().turn_signal_info;
10141015

10151016
const Pose & current_pose = planner_data_->self_odometry->pose.pose;
1016-
const Pose & start_pose = status_.pull_out_path.start_pose;
1017-
const Pose & end_pose = status_.pull_out_path.end_pose;
1018-
1019-
// turn on hazard light when backward driving
1020-
if (!status_.driving_forward) {
1021-
turn_signal.hazard_signal.command = HazardLightsCommand::ENABLE;
1022-
const auto back_start_pose = planner_data_->route_handler->getOriginalStartPose();
1023-
turn_signal.desired_start_point = back_start_pose;
1024-
turn_signal.required_start_point = back_start_pose;
1025-
// pull_out start_pose is same to backward driving end_pose
1026-
turn_signal.required_end_point = start_pose;
1027-
turn_signal.desired_end_point = start_pose;
1028-
return turn_signal;
1029-
}
1017+
const auto shift_start_idx =
1018+
motion_utils::findNearestIndex(path.points, status_.pull_out_path.start_pose.position);
1019+
const auto shift_end_idx =
1020+
motion_utils::findNearestIndex(path.points, status_.pull_out_path.end_pose.position);
1021+
const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_);
10301022

1031-
// turn on right signal until passing pull_out end point
1032-
const auto path = getFullPath();
1033-
// pull out path does not overlap
1034-
const double distance_from_end =
1035-
motion_utils::calcSignedArcLength(path.points, end_pose.position, current_pose.position);
1023+
const auto is_ignore_signal = [this](const lanelet::Id & id) {
1024+
if (!ignore_signal_.has_value()) {
1025+
return false;
1026+
}
1027+
return ignore_signal_.value() == id;
1028+
};
10361029

1037-
if (path.points.empty()) {
1038-
return {};
1039-
}
1030+
const auto update_ignore_signal = [this](const lanelet::Id & id, const bool is_ignore) {
1031+
return is_ignore ? std::make_optional(id) : std::nullopt;
1032+
};
10401033

1041-
// calculate lateral offset from pull out target lane center line
1042-
lanelet::ConstLanelet closest_road_lane;
1043-
const double backward_path_length =
1044-
planner_data_->parameters.backward_path_length + parameters_->max_back_distance;
1045-
const auto road_lanes = utils::getExtendedCurrentLanes(
1046-
planner_data_, backward_path_length, std::numeric_limits<double>::max(),
1047-
/*forward_only_in_route*/ true);
1048-
lanelet::utils::query::getClosestLanelet(road_lanes, start_pose, &closest_road_lane);
1049-
const double lateral_offset =
1050-
lanelet::utils::getLateralDistanceToCenterline(closest_road_lane, start_pose);
1051-
1052-
if (distance_from_end < 0.0 && lateral_offset > parameters_->th_turn_signal_on_lateral_offset) {
1053-
turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT;
1054-
} else if (
1055-
distance_from_end < 0.0 && lateral_offset < -parameters_->th_turn_signal_on_lateral_offset) {
1056-
turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT;
1057-
} else {
1058-
turn_signal.turn_signal.command = TurnIndicatorsCommand::DISABLE;
1034+
lanelet::Lanelet closest_lanelet;
1035+
lanelet::utils::query::getClosestLanelet(current_lanes, current_pose, &closest_lanelet);
1036+
1037+
if (is_ignore_signal(closest_lanelet.id())) {
1038+
return getPreviousModuleOutput().turn_signal_info;
10591039
}
10601040

1061-
turn_signal.desired_start_point = start_pose;
1062-
turn_signal.required_start_point = start_pose;
1063-
turn_signal.desired_end_point = end_pose;
1064-
1065-
// check if intersection exists within search length
1066-
const bool is_near_intersection = std::invoke([&]() {
1067-
const double check_length = parameters_->intersection_search_length;
1068-
double accumulated_length = 0.0;
1069-
const size_t current_idx = motion_utils::findNearestIndex(path.points, current_pose.position);
1070-
for (size_t i = current_idx; i < path.points.size() - 1; ++i) {
1071-
const auto & p = path.points.at(i);
1072-
for (const auto & lane : planner_data_->route_handler->getLaneletsFromIds(p.lane_ids)) {
1073-
const std::string turn_direction = lane.attributeOr("turn_direction", "else");
1074-
if (turn_direction == "right" || turn_direction == "left" || turn_direction == "straight") {
1075-
return true;
1076-
}
1077-
}
1078-
accumulated_length += tier4_autoware_utils::calcDistance2d(p, path.points.at(i + 1));
1079-
if (accumulated_length > check_length) {
1080-
return false;
1081-
}
1041+
const double current_shift_length =
1042+
lanelet::utils::getArcCoordinates(current_lanes, current_pose).distance;
1043+
1044+
constexpr bool egos_lane_is_shifted = true;
1045+
constexpr bool is_pull_out = true;
1046+
1047+
// In Geometric pull out, the ego stops once and then steers the wheels to the opposite direction.
1048+
// This sometimes causes the getBehaviorTurnSignalInfo method to detect the ego as stopped and
1049+
// close to complete its shift, so it wrongly turns off the blinkers, this override helps avoid
1050+
// this issue.
1051+
const bool override_ego_stopped_check = std::invoke([&]() {
1052+
if (status_.planner_type != PlannerType::GEOMETRIC) {
1053+
return false;
10821054
}
1083-
return false;
1055+
constexpr double distance_threshold = 1.0;
1056+
const auto stop_point = status_.pull_out_path.partial_paths.front().points.back();
1057+
const double distance_from_ego_to_stop_point = std::abs(motion_utils::calcSignedArcLength(
1058+
path.points, stop_point.point.pose.position, current_pose.position));
1059+
return distance_from_ego_to_stop_point < distance_threshold;
10841060
});
10851061

1086-
if (is_near_intersection) {
1087-
// offset required end pose with ration to activate turn signal for intersection
1088-
turn_signal.required_end_point = std::invoke([&]() {
1089-
const double length_start_to_end =
1090-
motion_utils::calcSignedArcLength(path.points, start_pose.position, end_pose.position);
1091-
const auto ratio = std::clamp(
1092-
parameters_->length_ratio_for_turn_signal_deactivation_near_intersection, 0.0, 1.0);
1093-
1094-
const double required_end_length = length_start_to_end * ratio;
1095-
double accumulated_length = 0.0;
1096-
const size_t start_idx = motion_utils::findNearestIndex(path.points, start_pose.position);
1097-
for (size_t i = start_idx; i < path.points.size() - 1; ++i) {
1098-
accumulated_length +=
1099-
tier4_autoware_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1));
1100-
if (accumulated_length > required_end_length) {
1101-
return path.points.at(i).point.pose;
1102-
}
1103-
}
1104-
// not found required end point
1105-
return end_pose;
1106-
});
1107-
} else {
1108-
turn_signal.required_end_point = end_pose;
1109-
}
1062+
const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo(
1063+
path, shift_start_idx, shift_end_idx, current_lanes, current_shift_length,
1064+
status_.driving_forward, egos_lane_is_shifted, override_ego_stopped_check, is_pull_out);
1065+
ignore_signal_ = update_ignore_signal(closest_lanelet.id(), is_ignore);
1066+
1067+
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
1068+
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(path.points);
1069+
const auto output_turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
1070+
path, current_pose, current_seg_idx, original_signal, new_signal,
1071+
planner_data_->parameters.ego_nearest_dist_threshold,
1072+
planner_data_->parameters.ego_nearest_yaw_threshold);
11101073

1111-
return turn_signal;
1074+
return output_turn_signal_info;
11121075
}
11131076

11141077
bool StartPlannerModule::isSafePath() const

0 commit comments

Comments
 (0)