Skip to content

Commit

Permalink
update avoidance config
Browse files Browse the repository at this point in the history
Signed-off-by: mitsudome-r <[email protected]>
  • Loading branch information
mitsudome-r committed Feb 28, 2025
1 parent 93874a0 commit bc740e6
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -122,8 +122,8 @@
motorcycle: true # [-]
pedestrian: true # [-]
# detection range
object_check_goal_distance: 20.0 # [m]
object_check_return_pose_distance: 20.0 # [m]
object_check_goal_distance: 2.0 # [m]
object_check_return_pose_distance: 2.0 # [m]
# lost object compensation
max_compensation_time: 2.0

Expand All @@ -150,9 +150,9 @@
# "auto" : generate candidate path. if RTC is running as AUTO mode, the ego avoids it automatically.
# "manual" : generate candidate path and wait operator approval even if RTC is running as AUTO mode.
# "ignore" : never avoid it.
policy: "manual" # [-]
policy: "auto" # [-]
condition:
th_stopped_time: 3.0 # [s]
th_stopped_time: 1.0 # [s]
th_moving_distance: 1.0 # [m]
ignore_area:
traffic_light:
Expand Down Expand Up @@ -243,7 +243,7 @@
return_dead_line:
goal:
enable: true # [-]
buffer: 3.0 # [m]
buffer: 1.0 # [m]
traffic_light:
enable: true # [-]
buffer: 3.0 # [m]
Expand Down Expand Up @@ -329,9 +329,9 @@
debug:
enable_other_objects_marker: true
enable_other_objects_info: true
enable_detection_area_marker: false
enable_drivable_bound_marker: false
enable_safety_check_marker: false
enable_shift_line_marker: false
enable_lane_marker: false
enable_misc_marker: false
enable_detection_area_marker: true
enable_drivable_bound_marker: true
enable_safety_check_marker: true
enable_shift_line_marker: true
enable_lane_marker: true
enable_misc_marker: true
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,19 @@
idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s]
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss]
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss]
safe_distance_margin : 4.0 # This is also used as a stop margin [m]
terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
safe_distance_margin : 1.0 # This is also used as a stop margin [m]
terminal_safe_distance_margin : 1.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s]
hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m]
slow_down_min_acc: -1.0 # slow down min deceleration [m/ss]
slow_down_min_jerk: -1.0 # slow down min jerk [m/sss]

nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index
min_behavior_stop_margin: 3.0 # [m]
min_behavior_stop_margin: 1.0 # [m]
stop_on_curve:
enable_approaching: false
additional_safe_distance_margin: 3.0 # [m]
additional_safe_distance_margin: 1.0 # [m]
min_safe_distance_margin: 3.0 # [m]
suppress_sudden_obstacle_stop: true

Expand Down Expand Up @@ -83,7 +83,7 @@
pointcloud: true

behavior_determination:
pointcloud_search_radius: 5.0
pointcloud_search_radius: 2.0
pointcloud_voxel_grid_x: 0.05
pointcloud_voxel_grid_y: 0.05
pointcloud_voxel_grid_z: 100000.0
Expand All @@ -108,8 +108,8 @@
obstacle_traj_angle_threshold : 0.523599 # [rad] = 30 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop

stop:
max_lat_margin: 0.3 # lateral margin between the obstacles and ego's footprint
max_lat_margin_against_unknown: 0.3 # lateral margin between the unknown obstacles and ego's footprint
max_lat_margin: 0.2 # lateral margin between the obstacles and ego's footprint
max_lat_margin_against_unknown: 0.2 # lateral margin between the unknown obstacles and ego's footprint
min_velocity_to_reach_collision_point: 2.0 # minimum velocity margin to calculate time to reach collision [m/s]
outside_obstacle:
max_lateral_time_margin: 4.5 # time threshold of lateral margin between the obstacles and ego's footprint [s]
Expand Down

0 comments on commit bc740e6

Please sign in to comment.