|
| 1 | +simple_planning_simulator {#simple_planning_simulator-package-design} |
| 2 | +=========== |
| 3 | + |
| 4 | + |
| 5 | +# Purpose / Use cases |
| 6 | + |
| 7 | +This node simulates the vehicle motion for a vehicle command in 2D using a simple vehicle model. |
| 8 | + |
| 9 | + |
| 10 | + |
| 11 | +# Design |
| 12 | + |
| 13 | + |
| 14 | +The purpose of this simulator is for the integration test of planning and control modules. This does not simulate sensing or perception, but is implemented in pure c++ only and works without GPU. |
| 15 | + |
| 16 | +## Assumptions / Known limits |
| 17 | + |
| 18 | + - It simulates only in 2D motion. |
| 19 | + - It does not perform physical operations such as collision and sensing, but only calculates the integral results of vehicle dynamics. |
| 20 | + |
| 21 | + |
| 22 | +## Inputs / Outputs / API |
| 23 | + |
| 24 | + |
| 25 | +**input** |
| 26 | + - input/vehicle_control_command [`autoware_auto_msgs/msg/VehicleControlCommand`] : target command to drive a vehicle. |
| 27 | + - input/ackermann_control_command [`autoware_auto_msgs/msg/AckermannControlCommand`] : target command to drive a vehicle. |
| 28 | + - input/vehicle_state_command [`autoware_auto_msgs/msg/VehicleStateCommand`] : target state command (e.g. gear). |
| 29 | + - /initialpose [`geometry_msgs/msg/PoseWithCovarianceStamped`] : for initial pose |
| 30 | + |
| 31 | +**output** |
| 32 | + - /tf [`tf2_msgs/msg/TFMessage`] : simulated vehicle pose (base_link) |
| 33 | + - /vehicle/vehicle_kinematic_state [`autoware_auto_msgs/msg/VehicleKinematicState`] : simulated kinematic state (defined in CoM) |
| 34 | + - /vehicle/state_report [`autoware_auto_msgs/msg/VehicleStateReport`] : current vehicle state (e.g. gear, mode, etc.) |
| 35 | + |
| 36 | + |
| 37 | +## Inner-workings / Algorithms |
| 38 | + |
| 39 | +### Common Parameters |
| 40 | + |
| 41 | +|Name|Type|Description|Default value| |
| 42 | +|:---|:---|:---|:---| |
| 43 | +|simulated_frame_id | string | set to the child_frame_id in output tf |"base_link"| |
| 44 | +|origin_frame_id | string | set to the frame_id in output tf |"odom"| |
| 45 | +|initialize_source | string | If "ORIGIN", the initial pose is set at (0,0,0). If "INITIAL_POSE_TOPIC", node will wait until the `/initialpose` topic is published. | "INITIAL_POSE_TOPIC" | "INITIAL_POSE_TOPIC" | |
| 46 | +|add_measurement_noise | bool | If true, the Gaussian noise is added to the simulated results.| true| |
| 47 | +|pos_noise_stddev | double | Standard deviation for position noise | 0.01| |
| 48 | +|rpy_noise_stddev | double | Standard deviation for Euler angle noise| 0.0001| |
| 49 | +|vel_noise_stddev | double | Standard deviation for longitudinal velocity noise | 0.0| |
| 50 | +|angvel_noise_stddev | double | Standard deviation for angular velocity noise| 0.0| |
| 51 | +|steer_noise_stddev | double | Standard deviation for steering angle noise| 0.0001| |
| 52 | + |
| 53 | + |
| 54 | + |
| 55 | +### Vehicle Model Parameters |
| 56 | + |
| 57 | + |
| 58 | +**vehicle_model_type options** |
| 59 | + |
| 60 | + - `IDEAL_STEER_VEL` |
| 61 | + - `IDEAL_STEER_ACC` |
| 62 | + - `IDEAL_STEER_ACC_GEARED` |
| 63 | + - `DELAY_STEER_ACC` |
| 64 | + - `DELAY_STEER_ACC_GEARED` |
| 65 | + |
| 66 | +The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves based on a 1st-order with time delay model. The `STEER` means the model receives the steer command. The `VEL` means the model receives the target velocity command, while the `ACC` model receives the target acceleration command. The `GEARED` suffix means that the motion will consider the gear command: the vehicle moves only one direction following the gear. |
| 67 | + |
| 68 | +The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). |
| 69 | + |
| 70 | + |
| 71 | +|Name|Type|Description|I_ST_V|I_ST_A|I_ST_A_G|D_ST_A|D_ST_A_G|Default value| unit | |
| 72 | +|:---|:---|:---|:---|:---|:---|:---|:---|:---|:---| |
| 73 | +|acc_time_delay | double | dead time for the acceleration input | x | x | x | o | o | 0.1 | [s] | |
| 74 | +|steer_time_delay | double | dead time for the steering input | x | x | x | o | o | 0.24| [s] | |
| 75 | +|acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | o | o | 0.1 | [s] | |
| 76 | +|steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | 0.27| [s] | |
| 77 | +|vel_lim | double | limit of velocity | x | x | x | o | o | 50.0| [m/s] | |
| 78 | +|vel_rate_lim | double | limit of acceleration | x | x | x | o | o | 7.0 | [m/ss] | |
| 79 | +|steer_lim | double | limit of steering angle | x | x | x | o | o | 1.0 | [rad] | |
| 80 | +|steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | 5.0 | [rad/s] | |
| 81 | +<!-- |deadzone_delta_steer | double | dead zone for the steering dynamics | x | x | x | o | o | 0.0 | [rad] | --> |
| 82 | + |
| 83 | + |
| 84 | +*Note*: The steering/velocity/acceleration dynamics is modeled by a first order system with a deadtime in a *delay* model. The definition of the *time constant* is the time it takes for the step response to rise up to 63% of its final value. The *deadtime* is a delay in the response to a control input. |
| 85 | + |
| 86 | + |
| 87 | +### Default TF configuration |
| 88 | + |
| 89 | +Since the vehicle outputs `odom`->`base_link` tf, this simulator outputs the tf with the same frame_id configuration. |
| 90 | +In the simple_planning_simulator.launch.py, the node that outputs the `map`->`odom` tf, that usually estimated by the localization module (e.g. NDT), will be launched as well. Since the tf output by this simulator module is an ideal value, `odom`->`map` will always be 0. |
| 91 | + |
| 92 | + |
| 93 | +## Error detection and handling |
| 94 | + |
| 95 | +The only validation on inputs being done is testing for a valid vehicle model type. |
| 96 | + |
| 97 | + |
| 98 | +# Security considerations |
| 99 | +<!-- Required --> |
| 100 | +<!-- Things to consider: |
| 101 | +- Spoofing (How do you check for and handle fake input?) |
| 102 | +- Tampering (How do you check for and handle tampered input?) |
| 103 | +- Repudiation (How are you affected by the actions of external actors?). |
| 104 | +- Information Disclosure (Can data leak?). |
| 105 | +- Denial of Service (How do you handle spamming?). |
| 106 | +- Elevation of Privilege (Do you need to change permission levels during execution?) --> |
| 107 | + |
| 108 | + |
| 109 | +# References / External links |
| 110 | +This is originally developed in the Autoware.AI. See the link below. |
| 111 | + |
| 112 | +https://github.com/Autoware-AI/simulation/tree/master/wf_simulator |
| 113 | + |
| 114 | +# Future extensions / Unimplemented parts |
| 115 | + |
| 116 | + - Improving the accuracy of vehicle models (e.g., adding steering dead zones and slip behavior) |
| 117 | + - Cooperation with modules that output pseudo pointcloud or pseudo perception results |
| 118 | + |
| 119 | + |
| 120 | +# Related issues |
| 121 | + |
| 122 | + - #1142: Follow-up to #570 - Integrate simple_planning_simulator Into CI |
0 commit comments