|
| 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 | + |
0 commit comments