ros2_control - rolling
steering_odometry.hpp
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_ODOMETRY_HPP_
19 #define STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_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_odometry
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 
47 {
48 public:
56  explicit SteeringOdometry(size_t velocity_rolling_window_size = 10);
57 
62  void init(const rclcpp::Time & time);
63 
72  const double traction_wheel_pos, const double steer_pos, const double dt);
73 
83  const double right_traction_wheel_pos, const double left_traction_wheel_pos,
84  const double steer_pos, const double dt);
85 
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 
107  const double traction_wheel_vel, const double steer_pos, const double dt);
108 
118  const double right_traction_wheel_vel, const double left_traction_wheel_vel,
119  const double steer_pos, const double dt);
120 
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 
140  void update_open_loop(const double v_bx, const double omega_bz, const double dt);
141 
146  void set_odometry_type(const unsigned int type);
147 
152  double get_heading() const { return heading_; }
153 
158  double get_x() const { return x_; }
159 
164  double get_y() const { return y_; }
165 
170  double get_linear() const { return linear_; }
171 
176  double get_angular() const { return angular_; }
177 
181  void set_wheel_params(
182  const double wheel_radius, const double wheelbase = 0.0, const double wheel_track = 0.0);
183 
188  void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size);
189 
197  std::tuple<std::vector<double>, std::vector<double>> get_commands(
198  const double v_bx, const double omega_bz, const bool open_loop = true);
199 
203  void reset_odometry();
204 
205 private:
212  bool update_odometry(const double v_bx, const double omega_bz, const double dt);
213 
220  void integrate_runge_kutta_2(const double v_bx, const double omega_bz, const double dt);
221 
228  void integrate_fk(const double v_bx, const double omega_bz, const double dt);
229 
235  double convert_twist_to_steering_angle(const double v_bx, const double omega_bz);
236 
243  double get_linear_velocity_double_traction_axle(
244  const double right_traction_wheel_vel, const double left_traction_wheel_vel,
245  const double steer_pos);
246 
250  void reset_accumulators();
251 
252 // \note The versions conditioning is added here to support the source-compatibility with Humble
253 #if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
254  using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
255 #else
256  using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
257 #endif
258 
260  rclcpp::Time timestamp_;
261 
263  double x_; // [m]
264  double y_; // [m]
265  double steer_pos_; // [rad]
266  double heading_; // [rad]
267 
269  double linear_; // [m/s]
270  double angular_; // [rad/s]
271 
273  double wheel_track_; // [m]
274  double wheelbase_; // [m]
275  double wheel_radius_; // [m]
276 
278  int config_type_ = -1;
279 
281  double traction_wheel_old_pos_;
282  double traction_right_wheel_old_pos_;
283  double traction_left_wheel_old_pos_;
285  size_t velocity_rolling_window_size_;
286  RollingMeanAccumulator linear_acc_;
287  RollingMeanAccumulator angular_acc_;
288 };
289 } // namespace steering_odometry
290 
291 #endif // STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition: steering_odometry.hpp:47
double get_heading() const
heading getter
Definition: steering_odometry.hpp:152
SteeringOdometry(size_t velocity_rolling_window_size=10)
Constructor Timestamp will get the current time value Value will be set to zero.
Definition: steering_odometry.cpp:27
bool update_from_position(const double traction_wheel_pos, const double steer_pos, const double dt)
Updates the odometry class with latest wheels position.
Definition: steering_odometry.cpp:75
void set_wheel_params(const double wheel_radius, const double wheelbase=0.0, const double wheel_track=0.0)
Sets the wheel parameters: radius, separation and wheelbase.
Definition: steering_odometry.cpp:193
std::tuple< std::vector< double >, std::vector< double > > get_commands(const double v_bx, const double omega_bz, const bool open_loop=true)
Calculates inverse kinematics for the desired linear and angular velocities.
Definition: steering_odometry.cpp:219
double get_linear() const
linear velocity getter
Definition: steering_odometry.hpp:170
double get_angular() const
angular velocity getter
Definition: steering_odometry.hpp:176
double get_x() const
x position getter
Definition: steering_odometry.hpp:158
void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size)
Velocity rolling window size setter.
Definition: steering_odometry.cpp:200
void update_open_loop(const double v_bx, const double omega_bz, const double dt)
Updates the odometry class with latest velocity command.
Definition: steering_odometry.cpp:183
bool update_from_velocity(const double traction_wheel_vel, const double steer_pos, const double dt)
Updates the odometry class with latest wheels position.
Definition: steering_odometry.cpp:121
double get_y() const
y position getter
Definition: steering_odometry.hpp:164
void reset_odometry()
Reset poses, heading, and accumulators.
Definition: steering_odometry.cpp:310
void init(const rclcpp::Time &time)
Initialize the odometry.
Definition: steering_odometry.cpp:46
void set_odometry_type(const unsigned int type)
Set odometry type.
Definition: steering_odometry.cpp:207