Skip to content

Commit 5e0e938

Browse files
kyoichi-sugaharaKenji Miyaketaikitanaka31222-takeshikenji-miyake
authored
feat(simple_planning_simulator): add delay model of velocity and steering (autowarefoundation#235)
* add delay steer vel in psim Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * change wz to steer Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix param description Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * modify readme Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * modify cmake Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * ci: change file URL Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix: order to create callback (autowarefoundation#220) Signed-off-by: tanaka3 <ttatcoder@outlook.jp> Co-authored-by: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * chore: remove unnecessary depends (autowarefoundation#227) * ci: add check-build-depends.yaml Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * chore: simplify build_depends.repos Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * chore: remove exec_depend Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * chore: use register-autonomoustuff-repository Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * chore: add setup tasks to other workflows Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * ci: update .yamllint.yaml (autowarefoundation#229) * ci: update .yamllint.yaml Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * chore: fix for yamllint Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix: remove warning for compile error (autowarefoundation#198) * fix: fix compile error of pointcloud preprocessor Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix: fix compiler warning for had map utils Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix: fix compiler warning for behavior velocity planner Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix: fix compiler warning for compare map segmentation Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix: fix compiler warning for occupancy grid map outlier filter Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix: fix compiler warning for detection by tracker Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix: restore comment Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix: set control_mode false before autoware engage (autowarefoundation#232) * fix: set control_mode false before autoware engage Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * add input/engage remap in launch Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix: library path (autowarefoundation#225) Signed-off-by: taikitanaka3 <taiki.tanaka@tier4.jp> Co-authored-by: taikitanaka3 <taiki.tanaka@tier4.jp> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix: interpolation (autowarefoundation#791) (autowarefoundation#218) Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * add missing function definition in .cpp Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * set input and state for DELAY_STEER_VEL model Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * fix: fix typo Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> Co-authored-by: Kenji Miyake <kenji.miyake@tier4.jp> Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Takayuki Murooka <takayuki5168@gmail.com> Co-authored-by: taikitanaka3 <taiki.tanaka@tier4.jp> Co-authored-by: Tomoya Kimura <tomoya.kimura@tier4.jp>
1 parent 26e3862 commit 5e0e938

File tree

8 files changed

+284
-11
lines changed

8 files changed

+284
-11
lines changed

simulator/simple_planning_simulator/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
1616
src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp
1717
src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp
1818
src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp
19+
src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp
1920
src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp
2021
src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp
2122
)

simulator/simple_planning_simulator/design/simple_planning_simulator-design.md

+13-10
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,7 @@ The purpose of this simulator is for the integration test of planning and contro
6060
- `IDEAL_STEER_VEL`
6161
- `IDEAL_STEER_ACC`
6262
- `IDEAL_STEER_ACC_GEARED`
63+
- `DELAY_STEER_VEL`
6364
- `DELAY_STEER_ACC`
6465
- `DELAY_STEER_ACC_GEARED`
6566

@@ -68,16 +69,18 @@ The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves base
6869
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).
6970

7071

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] |
72+
|Name|Type|Description|I_ST_V|I_ST_A|I_ST_A_G|D_ST_V|D_ST_A|D_ST_A_G|Default value| unit |
73+
|:---|:---|:---|:---|:---|:---|:---|:---|:---|:---|:---|
74+
|acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | 0.1 | [s] |
75+
|steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | 0.24| [s] |
76+
|vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | 0.25| [s] |
77+
|acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | 0.1 | [s] |
78+
|steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | 0.27| [s] |
79+
|vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | 0.5 | [s] |
80+
|vel_lim | double | limit of velocity | x | x | x | o | o | o | 50.0| [m/s] |
81+
|vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | 7.0 | [m/ss] |
82+
|steer_lim | double | limit of steering angle | x | x | x | o | o | o | 1.0 | [rad] |
83+
|steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | 5.0 | [rad/s] |
8184
<!-- |deadzone_delta_steer | double | dead zone for the steering dynamics | x | x | x | o | o | 0.0 | [rad] | -->
8285

8386

simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -193,6 +193,7 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
193193
DELAY_STEER_ACC = 2,
194194
DELAY_STEER_ACC_GEARED = 3,
195195
IDEAL_STEER_VEL = 4,
196+
DELAY_STEER_VEL = 5
196197
} vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics
197198
std::shared_ptr<SimModelInterface> vehicle_model_ptr_; //!< @brief vehicle model pointer
198199

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

+1
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp"
2222
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp"
2323
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp"
24+
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp"
2425

2526

2627
#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,150 @@
1+
// Copyright 2021 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_VEL_HPP_
16+
#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_
17+
18+
#include <deque>
19+
#include <iostream>
20+
#include <queue>
21+
22+
#include "eigen3/Eigen/Core"
23+
#include "eigen3/Eigen/LU"
24+
25+
#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
26+
/**
27+
* @class SimModelDelaySteerVel
28+
* @brief calculate delay steering dynamics
29+
*/
30+
class SimModelDelaySteerVel : public SimModelInterface
31+
{
32+
public:
33+
/**
34+
* @brief constructor
35+
* @param [in] vx_lim velocity limit [m/s]
36+
* @param [in] steer_lim steering limit [rad]
37+
* @param [in] vx_rate_lim acceleration limit [m/ss]
38+
* @param [in] steer_rate_lim steering angular velocity limit [rad/ss]
39+
* @param [in] wheelbase vehicle wheelbase length [m]
40+
* @param [in] dt delta time information to set input buffer for delay
41+
* @param [in] vx_delay time delay for velocity command [s]
42+
* @param [in] vx_time_constant time constant for 1D model of velocity dynamics
43+
* @param [in] steer_delay time delay for steering command [s]
44+
* @param [in] steer_time_constant time constant for 1D model of steering dynamics
45+
*/
46+
SimModelDelaySteerVel(
47+
float64_t vx_lim, float64_t steer_lim, float64_t vx_rate_lim, float64_t steer_rate_lim,
48+
float64_t wheelbase, float64_t dt, float64_t vx_delay, float64_t vx_time_constant,
49+
float64_t steer_delay, float64_t steer_time_constant);
50+
51+
/**
52+
* @brief destructor
53+
*/
54+
~SimModelDelaySteerVel() = default;
55+
56+
private:
57+
const float64_t MIN_TIME_CONSTANT; //!< @brief minimum time constant
58+
59+
enum IDX
60+
{
61+
X = 0,
62+
Y,
63+
YAW,
64+
VX,
65+
STEER,
66+
};
67+
enum IDX_U
68+
{
69+
VX_DES = 0,
70+
STEER_DES,
71+
};
72+
73+
const float64_t vx_lim_; //!< @brief velocity limit
74+
const float64_t vx_rate_lim_; //!< @brief acceleration limit
75+
const float64_t steer_lim_; //!< @brief steering limit [rad]
76+
const float64_t steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s]
77+
const float64_t wheelbase_; //!< @brief vehicle wheelbase length [m]
78+
float64_t prev_vx_ = 0.0;
79+
float64_t current_ax_ = 0.0;
80+
81+
std::deque<float64_t> vx_input_queue_; //!< @brief buffer for velocity command
82+
std::deque<float64_t> steer_input_queue_; //!< @brief buffer for angular velocity command
83+
const float64_t vx_delay_; //!< @brief time delay for velocity command [s]
84+
const float64_t vx_time_constant_;
85+
//!< @brief time constant for 1D model of velocity dynamics
86+
const float64_t steer_delay_; //!< @brief time delay for angular-velocity command [s]
87+
const float64_t
88+
steer_time_constant_; //!< @brief time constant for 1D model of angular-velocity dynamics
89+
90+
/**
91+
* @brief set queue buffer for input command
92+
* @param [in] dt delta time
93+
*/
94+
void initializeInputQueue(const float64_t & dt);
95+
96+
/**
97+
* @brief get vehicle position x
98+
*/
99+
float64_t getX() override;
100+
101+
/**
102+
* @brief get vehicle position y
103+
*/
104+
float64_t getY() override;
105+
106+
/**
107+
* @brief get vehicle angle yaw
108+
*/
109+
float64_t getYaw() override;
110+
111+
/**
112+
* @brief get vehicle longitudinal velocity
113+
*/
114+
float64_t getVx() override;
115+
116+
/**
117+
* @brief get vehicle lateral velocity
118+
*/
119+
float64_t getVy() override;
120+
121+
/**
122+
* @brief get vehicle longitudinal acceleration
123+
*/
124+
float64_t getAx() override;
125+
126+
/**
127+
* @brief get vehicle angular-velocity wz
128+
*/
129+
float64_t getWz() override;
130+
131+
/**
132+
* @brief get vehicle steering angle
133+
*/
134+
float64_t getSteer() override;
135+
136+
/**
137+
* @brief update vehicle states
138+
* @param [in] dt delta time [s]
139+
*/
140+
void update(const float64_t & dt) override;
141+
142+
/**
143+
* @brief calculate derivative of states with delay steering model
144+
* @param [in] state current model state
145+
* @param [in] input input vector to model
146+
*/
147+
Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override;
148+
};
149+
150+
#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_

simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp

+13-1
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,8 @@ void SimplePlanningSimulator::initialize_vehicle_model()
178178
const float64_t steer_rate_lim = declare_parameter("steer_rate_lim", 5.0);
179179
const float64_t acc_time_delay = declare_parameter("acc_time_delay", 0.1);
180180
const float64_t acc_time_constant = declare_parameter("acc_time_constant", 0.1);
181+
const float64_t vel_time_delay = declare_parameter("vel_time_delay", 0.25);
182+
const float64_t vel_time_constant = declare_parameter("vel_time_constant", 0.5);
181183
const float64_t steer_time_delay = declare_parameter("steer_time_delay", 0.24);
182184
const float64_t steer_time_constant = declare_parameter("steer_time_constant", 0.27);
183185
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
@@ -192,6 +194,11 @@ void SimplePlanningSimulator::initialize_vehicle_model()
192194
} else if (vehicle_model_type_str == "IDEAL_STEER_ACC_GEARED") {
193195
vehicle_model_type_ = VehicleModelType::IDEAL_STEER_ACC_GEARED;
194196
vehicle_model_ptr_ = std::make_shared<SimModelIdealSteerAccGeared>(wheelbase);
197+
} else if (vehicle_model_type_str == "DELAY_STEER_VEL") {
198+
vehicle_model_type_ = VehicleModelType::DELAY_STEER_VEL;
199+
vehicle_model_ptr_ = std::make_shared<SimModelDelaySteerVel>(
200+
vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0,
201+
vel_time_delay, vel_time_constant, steer_time_delay, steer_time_constant);
195202
} else if (vehicle_model_type_str == "DELAY_STEER_ACC") {
196203
vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC;
197204
vehicle_model_ptr_ = std::make_shared<SimModelDelaySteerAcc>(
@@ -316,7 +323,8 @@ void SimplePlanningSimulator::set_input(const float steer, const float vel, cons
316323
acc = -accel;
317324
}
318325

319-
if (vehicle_model_type_ == VehicleModelType::IDEAL_STEER_VEL) {
326+
if (vehicle_model_type_ == VehicleModelType::IDEAL_STEER_VEL ||
327+
vehicle_model_type_ == VehicleModelType::DELAY_STEER_VEL) {
320328
input << vel, steer;
321329
} else if ( // NOLINT
322330
vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC ||
@@ -412,6 +420,10 @@ void SimplePlanningSimulator::set_initial_state(const Pose & pose, const Twist &
412420
vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC_GEARED)
413421
{
414422
state << x, y, yaw, vx;
423+
} else if ( // NOLINT
424+
vehicle_model_type_ == VehicleModelType::DELAY_STEER_VEL)
425+
{
426+
state << x, y, yaw, vx, steer;
415427
} else if ( // NOLINT
416428
vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC ||
417429
vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,104 @@
1+
// Copyright 2021 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+
#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp"
16+
17+
#include <algorithm>
18+
19+
SimModelDelaySteerVel::SimModelDelaySteerVel(
20+
float64_t vx_lim, float64_t steer_lim, float64_t vx_rate_lim, float64_t steer_rate_lim,
21+
float64_t wheelbase, float64_t dt, float64_t vx_delay, float64_t vx_time_constant,
22+
float64_t steer_delay, float64_t steer_time_constant)
23+
: SimModelInterface(5 /* dim x */, 2 /* dim u */),
24+
MIN_TIME_CONSTANT(0.03),
25+
vx_lim_(vx_lim),
26+
vx_rate_lim_(vx_rate_lim),
27+
steer_lim_(steer_lim),
28+
steer_rate_lim_(steer_rate_lim),
29+
wheelbase_(wheelbase),
30+
vx_delay_(vx_delay),
31+
vx_time_constant_(std::max(vx_time_constant, MIN_TIME_CONSTANT)),
32+
steer_delay_(steer_delay),
33+
steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT))
34+
{
35+
initializeInputQueue(dt);
36+
}
37+
38+
float64_t SimModelDelaySteerVel::getX() { return state_(IDX::X); }
39+
float64_t SimModelDelaySteerVel::getY() { return state_(IDX::Y); }
40+
float64_t SimModelDelaySteerVel::getYaw() { return state_(IDX::YAW); }
41+
float64_t SimModelDelaySteerVel::getVx() { return state_(IDX::VX); }
42+
float64_t SimModelDelaySteerVel::getVy() {return 0.0;}
43+
float64_t SimModelDelaySteerVel::getAx() {return current_ax_;}
44+
float64_t SimModelDelaySteerVel::getWz()
45+
{
46+
return state_(IDX::VX) * std::tan(state_(IDX::STEER)) / wheelbase_;
47+
}
48+
float64_t SimModelDelaySteerVel::getSteer() {return state_(IDX::STEER);}
49+
void SimModelDelaySteerVel::update(const float64_t & dt)
50+
{
51+
Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_);
52+
53+
vx_input_queue_.push_back(input_(IDX_U::VX_DES));
54+
delayed_input(IDX_U::VX_DES) = vx_input_queue_.front();
55+
vx_input_queue_.pop_front();
56+
steer_input_queue_.push_back(input_(IDX_U::STEER_DES));
57+
delayed_input(IDX_U::STEER_DES) = steer_input_queue_.front();
58+
steer_input_queue_.pop_front();
59+
// do not use deadzone_delta_steer (Steer IF does not exist in this model)
60+
updateRungeKutta(dt, delayed_input);
61+
current_ax_ = (input_(IDX_U::VX_DES) - prev_vx_) / dt;
62+
prev_vx_ = input_(IDX_U::VX_DES);
63+
}
64+
65+
void SimModelDelaySteerVel::initializeInputQueue(const float64_t & dt)
66+
{
67+
size_t vx_input_queue_size = static_cast<size_t>(round(vx_delay_ / dt));
68+
for (size_t i = 0; i < vx_input_queue_size; i++) {
69+
vx_input_queue_.push_back(0.0);
70+
}
71+
size_t steer_input_queue_size = static_cast<size_t>(round(steer_delay_ / dt));
72+
for (size_t i = 0; i < steer_input_queue_size; i++) {
73+
steer_input_queue_.push_back(0.0);
74+
}
75+
}
76+
77+
78+
Eigen::VectorXd SimModelDelaySteerVel::calcModel(
79+
const Eigen::VectorXd & state, const Eigen::VectorXd & input)
80+
{
81+
auto sat = [](float64_t val, float64_t u, float64_t l) {return std::max(std::min(val, u), l);};
82+
83+
const float64_t vx = sat(state(IDX::VX), vx_lim_, -vx_lim_);
84+
const float64_t steer = sat(state(IDX::STEER), steer_lim_, -steer_lim_);
85+
const float64_t yaw = state(IDX::YAW);
86+
const float64_t delay_input_vx = input(IDX_U::VX_DES);
87+
const float64_t delay_input_steer = input(IDX_U::STEER_DES);
88+
const float64_t delay_vx_des = sat(delay_input_vx, vx_lim_, -vx_lim_);
89+
const float64_t delay_steer_des = sat(delay_input_steer, steer_lim_, -steer_lim_);
90+
float64_t vx_rate = -(vx - delay_vx_des) / vx_time_constant_;
91+
float64_t steer_rate = -(steer - delay_steer_des) / steer_time_constant_;
92+
vx_rate = sat(vx_rate, vx_rate_lim_, -vx_rate_lim_);
93+
steer_rate = sat(steer_rate, steer_rate_lim_, -steer_rate_lim_);
94+
95+
Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_);
96+
d_state(IDX::X) = vx * cos(yaw);
97+
d_state(IDX::Y) = vx * sin(yaw);
98+
d_state(IDX::YAW) = vx * std::tan(steer) / wheelbase_;
99+
d_state(IDX::VX) = vx_rate;
100+
d_state(IDX::STEER) = steer_rate;
101+
102+
return d_state;
103+
}
104+

simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ const std::vector<std::string> vehicle_model_type_vec = { // NOLINT
4242
"IDEAL_STEER_VEL",
4343
"IDEAL_STEER_ACC",
4444
"IDEAL_STEER_ACC_GEARED",
45+
"DELAY_STEER_VEL",
4546
"DELAY_STEER_ACC",
4647
"DELAY_STEER_ACC_GEARED",
4748
};

0 commit comments

Comments
 (0)