|
| 1 | +// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt) |
| 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 | +// Authors: dr. sc. Tomislav Petkovic, Dr. Ing. Denis Štogl |
| 16 | +// |
| 17 | + |
| 18 | +#ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_KINEMATICS_HPP_ |
| 19 | +#define STEERING_CONTROLLERS_LIBRARY__STEERING_KINEMATICS_HPP_ |
| 20 | + |
| 21 | +#include <cmath> |
| 22 | +#include <tuple> |
| 23 | +#include <vector> |
| 24 | + |
| 25 | +#include <rclcpp/time.hpp> |
| 26 | + |
| 27 | +// \note The versions conditioning is added here to support the source-compatibility with Humble |
| 28 | +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 |
| 29 | +#include "rcpputils/rolling_mean_accumulator.hpp" |
| 30 | +#else |
| 31 | +#include "rcppmath/rolling_mean_accumulator.hpp" |
| 32 | +#endif |
| 33 | + |
| 34 | +namespace steering_kinematics |
| 35 | +{ |
| 36 | +const unsigned int BICYCLE_CONFIG = 0; |
| 37 | +const unsigned int TRICYCLE_CONFIG = 1; |
| 38 | +const unsigned int ACKERMANN_CONFIG = 2; |
| 39 | + |
| 40 | +inline bool is_close_to_zero(double val) { return std::fabs(val) < 1e-6; } |
| 41 | + |
| 42 | +/** |
| 43 | + * \brief The SteeringKinematics class handles forward kinematics (odometry calculations) and |
| 44 | + * inverse kinematics (getting commands) (2D pose and velocity with related timestamp) |
| 45 | + */ |
| 46 | +class SteeringKinematics |
| 47 | +{ |
| 48 | +public: |
| 49 | + /** |
| 50 | + * \brief Constructor |
| 51 | + * Timestamp will get the current time value |
| 52 | + * Value will be set to zero |
| 53 | + * \param velocity_rolling_window_size Rolling window size used to compute the velocity mean |
| 54 | + * |
| 55 | + */ |
| 56 | + explicit SteeringKinematics(size_t velocity_rolling_window_size = 10); |
| 57 | + |
| 58 | + /** |
| 59 | + * \brief Initialize the SteeringKinematics class |
| 60 | + * \param time Current time |
| 61 | + */ |
| 62 | + void init(const rclcpp::Time & time); |
| 63 | + |
| 64 | + /** |
| 65 | + * \brief Updates the SteeringKinematics class with latest wheels position |
| 66 | + * \param traction_wheel_pos traction wheel position [rad] |
| 67 | + * \param steer_pos Steer wheel position [rad] |
| 68 | + * \param dt time difference to last call |
| 69 | + * \return true if the odometry is actually updated |
| 70 | + */ |
| 71 | + bool update_from_position( |
| 72 | + const double traction_wheel_pos, const double steer_pos, const double dt); |
| 73 | + |
| 74 | + /** |
| 75 | + * \brief Updates the SteeringKinematics class with latest wheels position |
| 76 | + * \param right_traction_wheel_pos Right traction wheel velocity [rad] |
| 77 | + * \param left_traction_wheel_pos Left traction wheel velocity [rad] |
| 78 | + * \param steer_pos Steer wheel position [rad] |
| 79 | + * \param dt time difference to last call |
| 80 | + * \return true if the odometry is actually updated |
| 81 | + */ |
| 82 | + bool update_from_position( |
| 83 | + const double right_traction_wheel_pos, const double left_traction_wheel_pos, |
| 84 | + const double steer_pos, const double dt); |
| 85 | + |
| 86 | + /** |
| 87 | + * \brief Updates the SteeringKinematics class with latest wheels position |
| 88 | + * \param right_traction_wheel_pos Right traction wheel position [rad] |
| 89 | + * \param left_traction_wheel_pos Left traction wheel position [rad] |
| 90 | + * \param right_steer_pos Right steer wheel position [rad] |
| 91 | + * \param left_steer_pos Left steer wheel position [rad] |
| 92 | + * \param dt time difference to last call |
| 93 | + * \return true if the odometry is actually updated |
| 94 | + */ |
| 95 | + bool update_from_position( |
| 96 | + const double right_traction_wheel_pos, const double left_traction_wheel_pos, |
| 97 | + const double right_steer_pos, const double left_steer_pos, const double dt); |
| 98 | + |
| 99 | + /** |
| 100 | + * \brief Updates the SteeringKinematics class with latest wheels position |
| 101 | + * \param traction_wheel_vel Traction wheel velocity [rad/s] |
| 102 | + * \param steer_pos Steer wheel position [rad] |
| 103 | + * \param dt time difference to last call |
| 104 | + * \return true if the odometry is actually updated |
| 105 | + */ |
| 106 | + bool update_from_velocity( |
| 107 | + const double traction_wheel_vel, const double steer_pos, const double dt); |
| 108 | + |
| 109 | + /** |
| 110 | + * \brief Updates the SteeringKinematics class with latest wheels position |
| 111 | + * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] |
| 112 | + * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] |
| 113 | + * \param steer_pos Steer wheel position [rad] |
| 114 | + * \param dt time difference to last call |
| 115 | + * \return true if the odometry is actually updated |
| 116 | + */ |
| 117 | + bool update_from_velocity( |
| 118 | + const double right_traction_wheel_vel, const double left_traction_wheel_vel, |
| 119 | + const double steer_pos, const double dt); |
| 120 | + |
| 121 | + /** |
| 122 | + * \brief Updates the SteeringKinematics class with latest wheels position |
| 123 | + * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] |
| 124 | + * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] |
| 125 | + * \param right_steer_pos Right steer wheel position [rad] |
| 126 | + * \param left_steer_pos Left steer wheel position [rad] |
| 127 | + * \param dt time difference to last call |
| 128 | + * \return true if the odometry is actually updated |
| 129 | + */ |
| 130 | + bool update_from_velocity( |
| 131 | + const double right_traction_wheel_vel, const double left_traction_wheel_vel, |
| 132 | + const double right_steer_pos, const double left_steer_pos, const double dt); |
| 133 | + |
| 134 | + /** |
| 135 | + * \brief Updates the SteeringKinematics class with latest velocity command |
| 136 | + * \param v_bx Linear velocity [m/s] |
| 137 | + * \param omega_bz Angular velocity [rad/s] |
| 138 | + * \param dt time difference to last call |
| 139 | + */ |
| 140 | + void update_open_loop(const double v_bx, const double omega_bz, const double dt); |
| 141 | + |
| 142 | + /** |
| 143 | + * \brief Set odometry type |
| 144 | + * \param type odometry type |
| 145 | + */ |
| 146 | + void set_odometry_type(const unsigned int type); |
| 147 | + |
| 148 | + /** |
| 149 | + * \brief Get odometry type |
| 150 | + * \return odometry type |
| 151 | + */ |
| 152 | + unsigned int get_odometry_type() const { return static_cast<unsigned int>(config_type_); } |
| 153 | + |
| 154 | + /** |
| 155 | + * \brief heading getter |
| 156 | + * \return heading [rad] |
| 157 | + */ |
| 158 | + double get_heading() const { return heading_; } |
| 159 | + |
| 160 | + /** |
| 161 | + * \brief x position getter |
| 162 | + * \return x position [m] |
| 163 | + */ |
| 164 | + double get_x() const { return x_; } |
| 165 | + |
| 166 | + /** |
| 167 | + * \brief y position getter |
| 168 | + * \return y position [m] |
| 169 | + */ |
| 170 | + double get_y() const { return y_; } |
| 171 | + |
| 172 | + /** |
| 173 | + * \brief linear velocity getter |
| 174 | + * \return linear velocity [m/s] |
| 175 | + */ |
| 176 | + double get_linear() const { return linear_; } |
| 177 | + |
| 178 | + /** |
| 179 | + * \brief angular velocity getter |
| 180 | + * \return angular velocity [rad/s] |
| 181 | + */ |
| 182 | + double get_angular() const { return angular_; } |
| 183 | + |
| 184 | + /** |
| 185 | + * \brief Sets the wheel parameters: radius, wheel_base, and wheel_track |
| 186 | + */ |
| 187 | + void set_wheel_params( |
| 188 | + const double wheel_radius, const double wheel_base = 0.0, const double wheel_track = 0.0); |
| 189 | + |
| 190 | + /** |
| 191 | + * \brief Sets the wheel parameters: radius, wheel_base, and wheel_track for steering and traction |
| 192 | + */ |
| 193 | + void set_wheel_params( |
| 194 | + const double wheel_radius, const double wheel_base, const double wheel_track_steering, |
| 195 | + const double wheel_track_traction); |
| 196 | + |
| 197 | + /** |
| 198 | + * \brief Velocity rolling window size setter |
| 199 | + * \param velocity_rolling_window_size Velocity rolling window size |
| 200 | + */ |
| 201 | + void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size); |
| 202 | + |
| 203 | + /** |
| 204 | + * \brief Calculates inverse kinematics for the desired linear and angular velocities |
| 205 | + * \param v_bx Desired linear velocity of the robot in x_b-axis direction |
| 206 | + * \param omega_bz Desired angular velocity of the robot around x_z-axis |
| 207 | + * \param open_loop If false, the IK will be calculated using measured steering angle |
| 208 | + * \param reduce_wheel_speed_until_steering_reached Reduce wheel speed until the steering angle |
| 209 | + * has been reached |
| 210 | + * \return Tuple of velocity commands and steering commands |
| 211 | + */ |
| 212 | + std::tuple<std::vector<double>, std::vector<double>> get_commands( |
| 213 | + const double v_bx, const double omega_bz, const bool open_loop = true, |
| 214 | + const bool reduce_wheel_speed_until_steering_reached = false); |
| 215 | + |
| 216 | + /** |
| 217 | + * \brief Reset poses, heading, and accumulators |
| 218 | + */ |
| 219 | + void reset_odometry(); |
| 220 | + |
| 221 | +private: |
| 222 | + /** |
| 223 | + * \brief Uses precomputed linear and angular velocities to compute odometry |
| 224 | + * \param v_bx Linear velocity [m/s] |
| 225 | + * \param omega_bz Angular velocity [rad/s] |
| 226 | + * \param dt time difference to last call |
| 227 | + */ |
| 228 | + bool update_odometry(const double v_bx, const double omega_bz, const double dt); |
| 229 | + |
| 230 | + /** |
| 231 | + * \brief Integrates the velocities (linear and angular) using 2nd order Runge-Kutta |
| 232 | + * \param v_bx Linear velocity [m/s] |
| 233 | + * \param omega_bz Angular velocity [rad/s] |
| 234 | + * \param dt time difference to last call |
| 235 | + */ |
| 236 | + void integrate_runge_kutta_2(const double v_bx, const double omega_bz, const double dt); |
| 237 | + |
| 238 | + /** |
| 239 | + * \brief Integrates the velocities (linear and angular) |
| 240 | + * \param v_bx Linear velocity [m/s] |
| 241 | + * \param omega_bz Angular velocity [rad/s] |
| 242 | + * \param dt time difference to last call |
| 243 | + */ |
| 244 | + void integrate_fk(const double v_bx, const double omega_bz, const double dt); |
| 245 | + |
| 246 | + /** |
| 247 | + * \brief Calculates steering angle from the desired twist |
| 248 | + * \param v_bx Linear velocity of the robot in x_b-axis direction |
| 249 | + * \param omega_bz Angular velocity of the robot around x_z-axis |
| 250 | + */ |
| 251 | + double convert_twist_to_steering_angle(const double v_bx, const double omega_bz); |
| 252 | + |
| 253 | + /** |
| 254 | + * \brief Calculates linear velocity of a robot with double traction axle |
| 255 | + * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] |
| 256 | + * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] |
| 257 | + * \param steer_pos Steer wheel position [rad] |
| 258 | + */ |
| 259 | + double get_linear_velocity_double_traction_axle( |
| 260 | + const double right_traction_wheel_vel, const double left_traction_wheel_vel, |
| 261 | + const double steer_pos); |
| 262 | + |
| 263 | + /** |
| 264 | + * \brief Reset linear and angular accumulators |
| 265 | + */ |
| 266 | + void reset_accumulators(); |
| 267 | + |
| 268 | +// \note The versions conditioning is added here to support the source-compatibility with Humble |
| 269 | +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 |
| 270 | + using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>; |
| 271 | +#else |
| 272 | + using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>; |
| 273 | +#endif |
| 274 | + |
| 275 | + /// Current timestamp: |
| 276 | + rclcpp::Time timestamp_; |
| 277 | + |
| 278 | + /// Current pose: |
| 279 | + double x_; // [m] |
| 280 | + double y_; // [m] |
| 281 | + double steer_pos_; // [rad] |
| 282 | + double heading_; // [rad] |
| 283 | + |
| 284 | + /// Current velocity: |
| 285 | + double linear_; // [m/s] |
| 286 | + double angular_; // [rad/s] |
| 287 | + |
| 288 | + /// Kinematic parameters |
| 289 | + double wheel_track_traction_; // [m] |
| 290 | + double wheel_track_steering_; // [m] |
| 291 | + double wheel_base_; // [m] |
| 292 | + double wheel_radius_; // [m] |
| 293 | + |
| 294 | + /// Configuration type used for the forward kinematics |
| 295 | + int config_type_ = -1; |
| 296 | + |
| 297 | + /// Previous wheel position/state [rad]: |
| 298 | + double traction_wheel_old_pos_; |
| 299 | + double traction_right_wheel_old_pos_; |
| 300 | + double traction_left_wheel_old_pos_; |
| 301 | + /// Rolling mean accumulators for the linear and angular velocities: |
| 302 | + size_t velocity_rolling_window_size_; |
| 303 | + RollingMeanAccumulator linear_acc_; |
| 304 | + RollingMeanAccumulator angular_acc_; |
| 305 | +}; |
| 306 | +} // namespace steering_kinematics |
| 307 | + |
| 308 | +#endif // STEERING_CONTROLLERS_LIBRARY__STEERING_KINEMATICS_HPP_ |
0 commit comments