Skip to content

Commit

Permalink
feat(autoware_behavior_velocity_traffic_light_module): adjust velocit…
Browse files Browse the repository at this point in the history
…y threshold for ensure stop at yellow light (#10064)

Signed-off-by: tomoya.kimura <[email protected]>
  • Loading branch information
tkimura4 authored Feb 4, 2025
1 parent 06794c3 commit a98a8f6
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@ This module is activated when there is traffic light in ego lane.

3. When vehicle current velocity is

- higher than 2.0m/s ⇒ pass judge(using next slide formula)
- higher than `yellow_light_stop_velocity` m/s ⇒ pass judge(using next slide formula)

- lower than 2.0m/s ⇒ stop
- lower than `yellow_light_stop_velocity` m/s ⇒ stop

4. When it to be judged that vehicle can’t stop before stop line, autoware chooses one of the following behaviors

Expand Down Expand Up @@ -69,13 +69,14 @@ This module is activated when there is traffic light in ego lane.

#### Module Parameters

| Parameter | Type | Description |
| ---------------------- | ------ | -------------------------------------------------------------------- |
| `stop_margin` | double | [m] margin before stop point |
| `tl_state_timeout` | double | [s] time out for detected traffic light result. |
| `stop_time_hysteresis` | double | [s] time threshold to decide stop planning for chattering prevention |
| `yellow_lamp_period` | double | [s] time for yellow lamp |
| `enable_pass_judge` | bool | [-] whether to use pass judge |
| Parameter | Type | Description |
| ---------------------------- | ------ | -------------------------------------------------------------------- |
| `stop_margin` | double | [m] margin before stop point |
| `tl_state_timeout` | double | [s] time out for detected traffic light result. |
| `stop_time_hysteresis` | double | [s] time threshold to decide stop planning for chattering prevention |
| `yellow_lamp_period` | double | [s] time for yellow lamp |
| `yellow_light_stop_velocity` | double | [m/s] velocity threshold for always stopping at a yellow light. |
| `enable_pass_judge` | bool | [-] whether to use pass judge |

#### Flowchart

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,6 @@
tl_state_timeout: 1.0
stop_time_hysteresis: 0.1
yellow_lamp_period: 2.75
yellow_light_stop_velocity: 1.0 # Velocity threshold (m/s) below which the vehicle will always stop before the traffic light when the signal turns yellow, regardless of the pass_judge decision.
enable_pass_judge: true
enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
planner_param_.enable_pass_judge = getOrDeclareParameter<bool>(node, ns + ".enable_pass_judge");
planner_param_.yellow_lamp_period =
getOrDeclareParameter<double>(node, ns + ".yellow_lamp_period");
planner_param_.yellow_light_stop_velocity =
getOrDeclareParameter<double>(node, ns + ".yellow_light_stop_velocity");
pub_tl_state_ = node.create_publisher<autoware_perception_msgs::msg::TrafficLightGroup>(
"~/output/traffic_signal", 1);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,8 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
delay_response_time);

const bool distance_stoppable = pass_judge_line_distance < signed_arc_length;
const bool slow_velocity = planner_data_->current_velocity->twist.linear.x < 2.0;
const bool slow_velocity =
planner_data_->current_velocity->twist.linear.x < planner_param_.yellow_light_stop_velocity;
const bool stoppable = distance_stoppable || slow_velocity;
const bool reachable = signed_arc_length < reachable_distance;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC
double stop_margin;
double tl_state_timeout;
double yellow_lamp_period;
double yellow_light_stop_velocity;
double stop_time_hysteresis;
bool enable_pass_judge;
};
Expand Down

0 comments on commit a98a8f6

Please sign in to comment.