Skip to content

Commit 2ea3e1c

Browse files
danielsanchezarankarishma1911
authored andcommitted
feat(behavior_path_planner_common): add general method for calculating turn signal for bpp modules (autowarefoundation#6625)
add general method for calculating turn signal for bpp modules Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent f2c5062 commit 2ea3e1c

File tree

4 files changed

+383
-32
lines changed

4 files changed

+383
-32
lines changed

planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md

+32-32
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ Turn Signal decider determines necessary blinkers.
44

55
## Purpose / Role
66

7-
This module is responsible for activating a necessary blinker during driving. It uses rule-based algorithm to determine blinkers, and the details of this algorithm are described in the following sections. Note that this algorithm is strictly based on the Japanese Road Traffic Raw.
7+
This module is responsible for activating a necessary blinker during driving. It uses rule-based algorithm to determine blinkers, and the details of this algorithm are described in the following sections. Note that this algorithm is strictly based on the Japanese Road Traffic Law.
88

99
### Assumptions
1010

@@ -16,7 +16,7 @@ Autoware has following order of priorities for turn signals.
1616

1717
### Limitations
1818

19-
Currently, this algorithm can sometimes give unnatural (not wrong) blinkers in a complicated situations. This is because it tries to follow the road traffic raw and cannot solve `blinker conflicts` clearly in that environment.
19+
Currently, this algorithm can sometimes give unnatural (not wrong) blinkers in complicated situations. This is because it tries to follow the road traffic law and cannot solve `blinker conflicts` clearly in that environment.
2020

2121
## Parameters for turn signal decider
2222

@@ -59,16 +59,16 @@ For left turn, right turn, avoidance, lane change, goal planner and pull out, we
5959

6060
Turn signal decider checks each lanelet on the map if it has `turn_direction` information. If a lanelet has this information, it activates necessary blinker based on this information.
6161

62-
- desired start point
63-
The `search_distance` for blinkers at intersections is `v * turn_signal_search_time + turn_signal_intersection_search_distance`. Then the start point becomes `search_distance` meters before the start point of the intersection lanelet(depicted in gree in the following picture), where `v` is the velocity of the ego vehicle. However, if we set `turn_signal_distance` in the lanelet, we use that length as search distance.
62+
- desired start point
63+
The `search_distance` for blinkers at intersections is `v * turn_signal_search_time + turn_signal_intersection_search_distance`. Then the start point becomes `search_distance` meters before the start point of the intersection lanelet(depicted in green in the following picture), where `v` is the velocity of the ego vehicle. However, if we set `turn_signal_distance` in the lanelet, we use that length as search distance.
6464

65-
- desired end point
65+
- desired end point
6666
Terminal point of the intersection lanelet.
6767

68-
- required start point
68+
- required start point
6969
Initial point of the intersection lanelet.
7070

71-
- required end point
71+
- required end point
7272
The earliest point that satisfies the following condition. $\theta - \theta_{\textrm{end}} < \delta$, where $\theta_{\textrm{end}}$ is yaw angle of the terminal point of the lanelet, $\theta$ is the angle of a required end point and $\delta$ is the threshold defined by the user.
7373

7474
![section_turn_signal](../images/turn_signal_decider/left_right_turn.drawio.svg)
@@ -79,99 +79,99 @@ Avoidance can be separated into two sections, first section and second section.
7979

8080
First section
8181

82-
- desired start point
82+
- desired start point
8383
`v * turn_signal_search_time` meters before the start point of the avoidance shift path.
8484

85-
- desired end point
85+
- desired end point
8686
Shift complete point where the path shift is completed.
8787

88-
- required start point
88+
- required start point
8989
Avoidance start point.
9090

91-
- required end point
91+
- required end point
9292
Shift complete point same as the desired end point.
9393

9494
![section_first_avoidance](../images/turn_signal_decider/avoidance_first_section.drawio.svg)
9595

9696
Second section
9797

98-
- desired start point
98+
- desired start point
9999
Shift complete point.
100100

101-
- desired end point
101+
- desired end point
102102
Avoidance terminal point
103103

104-
- required start point
104+
- required start point
105105
Shift complete point.
106106

107-
- required end point
107+
- required end point
108108
Avoidance terminal point.
109109

110110
![section_second_avoidance](../images/turn_signal_decider/avoidance_second_section.drawio.svg)
111111

112112
#### 3. Lane Change
113113

114-
- desired start point
114+
- desired start point
115115
`v * turn_signal_search_time` meters before the start point of the lane change path.
116116

117-
- desired end point
117+
- desired end point
118118
Terminal point of the lane change path.
119119

120-
- required start point
120+
- required start point
121121
Initial point of the lane change path.
122122

123-
- required end point
123+
- required end point
124124
Cross point with lane change path and boundary line of the adjacent lane.
125125

126126
![section_lane_change](../images/turn_signal_decider/lane_change.drawio.svg)
127127

128128
#### 4. Pull out
129129

130-
- desired start point
130+
- desired start point
131131
Start point of the path of pull out.
132132

133-
- desired end point
133+
- desired end point
134134
Terminal point of the path of pull out.
135135

136-
- required start point
136+
- required start point
137137
Start point of the path pull out.
138138

139-
- required end point
139+
- required end point
140140
Terminal point of the path of pull out.
141141

142142
![section_pull_out](../images/turn_signal_decider/pull_out.drawio.svg)
143143

144144
#### 5. Goal Planner
145145

146-
- desired start point
146+
- desired start point
147147
`v * turn_signal_search_time` meters before the start point of the pull over path.
148148

149-
- desired end point
149+
- desired end point
150150
Terminal point of the path of pull over.
151151

152-
- required start point
152+
- required start point
153153
Start point of the path of pull over.
154154

155-
- required end point
155+
- required end point
156156
Terminal point of the path of pull over.
157157

158158
![section_pull_over](../images/turn_signal_decider/pull_over.drawio.svg)
159159

160160
When it comes to handle several blinkers, it gives priority to the first blinker that comes first. However, this rule sometimes activate unnatural blinkers, so turn signal decider uses the following five rules to decide the necessary turn signal.
161161

162-
- pattern1
162+
- pattern1
163163
![pattern1](../images/turn_signal_decider/pattern1.drawio.svg)
164164

165-
- pattern2
165+
- pattern2
166166
![pattern2](../images/turn_signal_decider/pattern2.drawio.svg)
167167

168-
- pattern3
168+
- pattern3
169169
![pattern3](../images/turn_signal_decider/pattern3.drawio.svg)
170170

171-
- pattern4
171+
- pattern4
172172
![pattern4](../images/turn_signal_decider/pattern4.drawio.svg)
173173

174-
- pattern5
174+
- pattern5
175175
![pattern5](../images/turn_signal_decider/pattern5.drawio.svg)
176176

177177
Based on these five rules, turn signal decider can solve `blinker conflicts`. The following pictures show some examples of this kind of conflicts.

planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp

+57
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include "motion_utils/trajectory/trajectory.hpp"
2222

2323
#include <lanelet2_extension/regulatory_elements/Forward.hpp>
24+
#include <lanelet2_extension/utility/utilities.hpp>
2425
#include <rclcpp/rclcpp/clock.hpp>
2526
#include <rclcpp/rclcpp/time.hpp>
2627
#include <route_handler/route_handler.hpp>
@@ -165,6 +166,62 @@ struct PlannerData
165166
mutable std::vector<double> drivable_area_expansion_prev_curvatures{};
166167
mutable TurnSignalDecider turn_signal_decider;
167168

169+
std::pair<TurnSignalInfo, bool> getBehaviorTurnSignalInfo(
170+
const PathWithLaneId & path, const size_t shift_start_idx, const size_t shift_end_idx,
171+
const lanelet::ConstLanelets & current_lanelets, const double current_shift_length,
172+
const bool is_driving_forward, const bool egos_lane_is_shifted,
173+
const bool override_ego_stopped_check = false, const bool is_pull_out = false) const
174+
{
175+
if (shift_start_idx + 1 > path.points.size()) {
176+
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
177+
return std::make_pair(TurnSignalInfo{}, true);
178+
}
179+
180+
if (shift_end_idx + 1 > path.points.size()) {
181+
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
182+
return std::make_pair(TurnSignalInfo{}, true);
183+
}
184+
185+
std::vector<double> lengths(path.points.size(), 0.0);
186+
ShiftedPath shifted_path{path, lengths};
187+
ShiftLine shift_line;
188+
189+
{
190+
const auto start_pose = path.points.at(shift_start_idx).point.pose;
191+
const auto start_shift_length =
192+
lanelet::utils::getArcCoordinates(current_lanelets, start_pose).distance;
193+
const auto end_pose = path.points.at(shift_end_idx).point.pose;
194+
const auto end_shift_length =
195+
lanelet::utils::getArcCoordinates(current_lanelets, end_pose).distance;
196+
shifted_path.shift_length.at(shift_start_idx) = start_shift_length;
197+
shifted_path.shift_length.at(shift_end_idx) = end_shift_length;
198+
199+
shift_line.start = start_pose;
200+
shift_line.end = end_pose;
201+
shift_line.start_shift_length = start_shift_length;
202+
shift_line.end_shift_length = end_shift_length;
203+
shift_line.start_idx = shift_start_idx;
204+
shift_line.end_idx = shift_end_idx;
205+
}
206+
207+
return turn_signal_decider.getBehaviorTurnSignalInfo(
208+
shifted_path, shift_line, current_lanelets, route_handler, parameters, self_odometry,
209+
current_shift_length, is_driving_forward, egos_lane_is_shifted, override_ego_stopped_check,
210+
is_pull_out);
211+
}
212+
213+
std::pair<TurnSignalInfo, bool> getBehaviorTurnSignalInfo(
214+
const ShiftedPath & path, const ShiftLine & shift_line,
215+
const lanelet::ConstLanelets & current_lanelets, const double current_shift_length,
216+
const bool is_driving_forward, const bool egos_lane_is_shifted,
217+
const bool override_ego_stopped_check = false, const bool is_pull_out = false) const
218+
{
219+
return turn_signal_decider.getBehaviorTurnSignalInfo(
220+
path, shift_line, current_lanelets, route_handler, parameters, self_odometry,
221+
current_shift_length, is_driving_forward, egos_lane_is_shifted, override_ego_stopped_check,
222+
is_pull_out);
223+
}
224+
168225
TurnIndicatorsCommand getTurnSignal(
169226
const PathWithLaneId & path, const TurnSignalInfo & turn_signal_info,
170227
TurnSignalDebugData & debug_data)

0 commit comments

Comments
 (0)