forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
fix: update simple planning simulator param file (autowarefoundation#179
) Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com>
- Loading branch information
1 parent
7e8fe73
commit 03d0573
Showing
1 changed file
with
20 additions
and
19 deletions.
There are no files selected for viewing
39 changes: 20 additions & 19 deletions
39
simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,21 +1,22 @@ | ||
simulation: | ||
simple_planning_simulator: | ||
ros__parameters: | ||
simulated_frame_id: "base_link" | ||
origin_frame_id: "map" | ||
vehicle_model_type: "DELAY_STEER_ACC_GEARED" | ||
initialize_source: "INITIAL_POSE_TOPIC" | ||
timer_sampling_time_ms: 25 | ||
add_measurement_noise: False | ||
vel_lim: 30.0 | ||
vel_rate_lim: 30.0 | ||
steer_lim: 0.6 | ||
steer_rate_lim: 6.28 | ||
acc_time_delay: 0.1 | ||
acc_time_constant: 0.1 | ||
steer_time_delay: 0.1 | ||
steer_time_constant: 0.1 | ||
x_stddev: 0.0001 # x standard deviation for dummy covariance in map coordinate | ||
y_stddev: 0.0001 # y standard deviation for dummy covariance in map coordinate | ||
/**: | ||
ros__parameters: | ||
simulation: | ||
simple_planning_simulator: | ||
simulated_frame_id: "base_link" | ||
origin_frame_id: "map" | ||
vehicle_model_type: "DELAY_STEER_ACC_GEARED" | ||
initialize_source: "INITIAL_POSE_TOPIC" | ||
timer_sampling_time_ms: 25 | ||
add_measurement_noise: False | ||
vel_lim: 30.0 | ||
vel_rate_lim: 30.0 | ||
steer_lim: 0.6 | ||
steer_rate_lim: 6.28 | ||
acc_time_delay: 0.1 | ||
acc_time_constant: 0.1 | ||
steer_time_delay: 0.1 | ||
steer_time_constant: 0.1 | ||
x_stddev: 0.0001 # x standard deviation for dummy covariance in map coordinate | ||
y_stddev: 0.0001 # y standard deviation for dummy covariance in map coordinate | ||
|
||
# Note: vehicle characteristics parameters (e.g. wheelbase) are defined in a separate file. |