Skip to content

Commit c7f2e1e

Browse files
feat(simple_planning_simulator): add new vehicle model with falling down (#7651)
* add new vehicle model Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent cfcf1e7 commit c7f2e1e

File tree

8 files changed

+380
-30
lines changed

8 files changed

+380
-30
lines changed

simulator/simple_planning_simulator/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
1919
src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp
2020
src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp
2121
src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp
22+
src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp
2223
src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp
2324
src/simple_planning_simulator/utils/csv_loader.cpp
2425
)

simulator/simple_planning_simulator/README.md

+21-20
Original file line numberDiff line numberDiff line change
@@ -62,33 +62,34 @@ The purpose of this simulator is for the integration test of planning and contro
6262
- `DELAY_STEER_VEL`
6363
- `DELAY_STEER_ACC`
6464
- `DELAY_STEER_ACC_GEARED`
65+
- `DELAY_STEER_ACC_GEARED_WO_FALL_GUARD`
6566
- `DELAY_STEER_MAP_ACC_GEARED`: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle.
6667
- `LEARNED_STEER_VEL`: launches learned python models. More about this [here](../learning_based_vehicle_model).
6768

6869
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.
6970

7071
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).
7172

72-
| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_M_ACC_G | L_S_V | Default value | unit |
73-
| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :----------- | :---- | :------------ | :------ |
74-
| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | x | 0.1 | [s] |
75-
| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | x | 0.24 | [s] |
76-
| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | 0.25 | [s] |
77-
| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | x | 0.1 | [s] |
78-
| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | x | 0.27 | [s] |
79-
| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | x | x | 0.0 | [rad] |
80-
| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | 0.5 | [s] |
81-
| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | x | 50.0 | [m/s] |
82-
| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | x | 7.0 | [m/ss] |
83-
| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | x | 1.0 | [rad] |
84-
| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | x | 5.0 | [rad/s] |
85-
| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | x | 0.0 | [rad] |
86-
| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | x | x | 1.0 | [-] |
87-
| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | x | x | 1.0 | [-] |
88-
| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | o | x | - | [-] |
89-
| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | o | - | [-] |
90-
| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | o | - | [-] |
91-
| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | o | - | [-] |
73+
| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_A_G_WO_FG | D_ST_M_ACC_G | L_S_V | Default value | unit |
74+
| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------- | :----------- | :---- | :------------ | :------ |
75+
| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | o | x | 0.1 | [s] |
76+
| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | o | x | 0.24 | [s] |
77+
| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | x | 0.25 | [s] |
78+
| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | o | x | 0.1 | [s] |
79+
| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | o | x | 0.27 | [s] |
80+
| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | o | x | x | 0.0 | [rad] |
81+
| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | x | 0.5 | [s] |
82+
| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | o | x | 50.0 | [m/s] |
83+
| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | o | x | 7.0 | [m/ss] |
84+
| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | o | x | 1.0 | [rad] |
85+
| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | o | x | 5.0 | [rad/s] |
86+
| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | o | x | 0.0 | [rad] |
87+
| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | o | x | x | 1.0 | [-] |
88+
| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | o | x | x | 1.0 | [-] |
89+
| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | x | o | x | - | [-] |
90+
| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | x | o | - | [-] |
91+
| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | x | o | - | [-] |
92+
| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | x | o | - | [-] |
9293

9394
_Note:_ Parameters `model_module_paths`, `model_param_paths`, and `model_class_names` need to have the same length.
9495

simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -205,7 +205,8 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
205205
IDEAL_STEER_VEL = 4,
206206
DELAY_STEER_VEL = 5,
207207
DELAY_STEER_MAP_ACC_GEARED = 6,
208-
LEARNED_STEER_VEL = 7
208+
LEARNED_STEER_VEL = 7,
209+
DELAY_STEER_ACC_GEARED_WO_FALL_GUARD = 8
209210
} vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics
210211
std::shared_ptr<SimModelInterface> vehicle_model_ptr_; //!< @brief vehicle model pointer
211212

simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp"
1919
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp"
20+
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp"
2021
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp"
2122
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp"
2223
#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp"
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,149 @@
1+
// Copyright 2024 The Autoware Foundation.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT
16+
#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT
17+
18+
#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
19+
20+
#include <Eigen/Core>
21+
#include <Eigen/LU>
22+
23+
#include <deque>
24+
#include <iostream>
25+
#include <queue>
26+
27+
class SimModelDelaySteerAccGearedWoFallGuard : public SimModelInterface
28+
{
29+
public:
30+
/**
31+
* @param [in] vx_lim velocity limit [m/s]
32+
* @param [in] steer_lim steering limit [rad]
33+
* @param [in] vx_rate_lim acceleration limit [m/ss]
34+
* @param [in] steer_rate_lim steering angular velocity limit [rad/ss]
35+
* @param [in] wheelbase vehicle wheelbase length [m]
36+
* @param [in] dt delta time information to set input buffer for delay
37+
* @param [in] acc_delay time delay for accel command [s]
38+
* @param [in] acc_time_constant time constant for 1D model of accel dynamics
39+
* @param [in] steer_delay time delay for steering command [s]
40+
* @param [in] steer_time_constant time constant for 1D model of steering dynamics
41+
* @param [in] steer_dead_band dead band for steering angle [rad]
42+
* @param [in] steer_bias steering bias [rad]
43+
* @param [in] debug_acc_scaling_factor scaling factor for accel command
44+
* @param [in] debug_steer_scaling_factor scaling factor for steering command
45+
*/
46+
SimModelDelaySteerAccGearedWoFallGuard(
47+
double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase,
48+
double dt, double acc_delay, double acc_time_constant, double steer_delay,
49+
double steer_time_constant, double steer_dead_band, double steer_bias,
50+
double debug_acc_scaling_factor, double debug_steer_scaling_factor);
51+
52+
/**
53+
* @brief default destructor
54+
*/
55+
~SimModelDelaySteerAccGearedWoFallGuard() = default;
56+
57+
private:
58+
const double MIN_TIME_CONSTANT; //!< @brief minimum time constant
59+
60+
enum IDX {
61+
X = 0,
62+
Y,
63+
YAW,
64+
VX,
65+
STEER,
66+
PEDAL_ACCX,
67+
};
68+
enum IDX_U { PEDAL_ACCX_DES = 0, GEAR, SLOPE_ACCX, STEER_DES };
69+
70+
const double vx_lim_; //!< @brief velocity limit [m/s]
71+
const double vx_rate_lim_; //!< @brief acceleration limit [m/ss]
72+
const double steer_lim_; //!< @brief steering limit [rad]
73+
const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s]
74+
const double wheelbase_; //!< @brief vehicle wheelbase length [m]
75+
76+
std::deque<double> acc_input_queue_; //!< @brief buffer for accel command
77+
std::deque<double> steer_input_queue_; //!< @brief buffer for steering command
78+
const double acc_delay_; //!< @brief time delay for accel command [s]
79+
const double acc_time_constant_; //!< @brief time constant for accel dynamics
80+
const double steer_delay_; //!< @brief time delay for steering command [s]
81+
const double steer_time_constant_; //!< @brief time constant for steering dynamics
82+
const double steer_dead_band_; //!< @brief dead band for steering angle [rad]
83+
const double steer_bias_; //!< @brief steering angle bias [rad]
84+
const double debug_acc_scaling_factor_; //!< @brief scaling factor for accel command
85+
const double debug_steer_scaling_factor_; //!< @brief scaling factor for steering command
86+
87+
/**
88+
* @brief set queue buffer for input command
89+
* @param [in] dt delta time
90+
*/
91+
void initializeInputQueue(const double & dt);
92+
93+
/**
94+
* @brief get vehicle position x
95+
*/
96+
double getX() override;
97+
98+
/**
99+
* @brief get vehicle position y
100+
*/
101+
double getY() override;
102+
103+
/**
104+
* @brief get vehicle angle yaw
105+
*/
106+
double getYaw() override;
107+
108+
/**
109+
* @brief get vehicle velocity vx
110+
*/
111+
double getVx() override;
112+
113+
/**
114+
* @brief get vehicle lateral velocity
115+
*/
116+
double getVy() override;
117+
118+
/**
119+
* @brief get vehicle longitudinal acceleration
120+
*/
121+
double getAx() override;
122+
123+
/**
124+
* @brief get vehicle angular-velocity wz
125+
*/
126+
double getWz() override;
127+
128+
/**
129+
* @brief get vehicle steering angle
130+
*/
131+
double getSteer() override;
132+
133+
/**
134+
* @brief update vehicle states
135+
* @param [in] dt delta time [s]
136+
*/
137+
void update(const double & dt) override;
138+
139+
/**
140+
* @brief calculate derivative of states with time delay steering model
141+
* @param [in] state current model state
142+
* @param [in] input input vector to model
143+
*/
144+
Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override;
145+
};
146+
147+
// clang-format off
148+
#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT
149+
// clang-format on

0 commit comments

Comments
 (0)