Skip to content

Commit

Permalink
refactor(behavior_velocity_stop_line_module): clean stop line module (a…
Browse files Browse the repository at this point in the history
  • Loading branch information
purewater0901 authored Jul 26, 2023
1 parent ffd2a4b commit e181dce
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 11 deletions.
12 changes: 7 additions & 5 deletions planning/behavior_velocity_stop_line_module/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,13 @@ This module is activated when there is a stop line in a target lane.

### Module Parameters

| Parameter | Type | Description |
| --------------------------- | ------ | ---------------------------------------------------------------------------------------------- |
| `stop_margin` | double | a margin that the vehicle tries to stop before stop_line |
| `stop_check_dist` | double | when the vehicle is within `stop_check_dist` from stop_line and stopped, move to STOPPED state |
| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section) |
| Parameter | Type | Description |
| -------------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `stop_margin` | double | a margin that the vehicle tries to stop before stop_line |
| `stop_duration_sec` | double | [s] time parameter for the ego vehicle to stop in front of a stop line |
| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section). Also, when the ego vehicle is within this distance from a stop line, the ego state becomes STOPPED from APPROACHING |
| `use_initialization_stop_state` | bool | A flag to determine whether to return to the approaching state when the vehicle moves away from a stop line. |
| `show_stop_line_collision_check` | bool | A flag to determine whether to show the debug information of collision check with a stop line |

### Inner-workings / Algorithms

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,9 @@
ros__parameters:
stop_line:
stop_margin: 0.0
stop_check_dist: 2.0
stop_duration_sec: 1.0
use_initialization_stop_line_state: true
hold_stop_margin_distance: 2.0

debug:
show_stopline_collision_check: false # [-] whether to show stopline collision
show_stop_line_collision_check: false # [-] whether to show stopline collision
2 changes: 1 addition & 1 deletion planning/behavior_velocity_stop_line_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ visualization_msgs::msg::MarkerArray createStopLineCollisionCheck(
visualization_msgs::msg::MarkerArray StopLineModule::createDebugMarkerArray()
{
visualization_msgs::msg::MarkerArray debug_marker_array;
if (planner_param_.show_stopline_collision_check) {
if (planner_param_.show_stop_line_collision_check) {
appendMarkerArray(
createStopLineCollisionCheck(debug_data_, module_id_), &debug_marker_array,
this->clock_->now());
Expand Down
4 changes: 2 additions & 2 deletions planning/behavior_velocity_stop_line_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node)
p.use_initialization_stop_line_state =
node.declare_parameter<bool>(ns + ".use_initialization_stop_line_state");
// debug
p.show_stopline_collision_check =
node.declare_parameter<bool>(ns + ".debug.show_stopline_collision_check");
p.show_stop_line_collision_check =
node.declare_parameter<bool>(ns + ".debug.show_stop_line_collision_check");
}

std::vector<StopLineWithLaneId> StopLineModuleManager::getStopLinesWithLaneIdOnPath(
Expand Down
2 changes: 1 addition & 1 deletion planning/behavior_velocity_stop_line_module/src/scene.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class StopLineModule : public SceneModuleInterface
double stop_duration_sec;
double hold_stop_margin_distance;
bool use_initialization_stop_line_state;
bool show_stopline_collision_check;
bool show_stop_line_collision_check;
};

public:
Expand Down

0 comments on commit e181dce

Please sign in to comment.