ros2_control - iron
Loading...
Searching...
No Matches
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 "realtime_tools/realtime_buffer.h"
26#include "realtime_tools/realtime_publisher.h"
27
28#include "rcpputils/rolling_mean_accumulator.hpp"
29
30namespace steering_odometry
31{
32const unsigned int BICYCLE_CONFIG = 0;
33const unsigned int TRICYCLE_CONFIG = 1;
34const unsigned int ACKERMANN_CONFIG = 2;
35
36inline bool is_close_to_zero(double val) { return std::fabs(val) < 1e-6; }
37
43{
44public:
52 explicit SteeringOdometry(size_t velocity_rolling_window_size = 10);
53
58 void init(const rclcpp::Time & time);
59
68 const double traction_wheel_pos, const double steer_pos, const double dt);
69
79 const double right_traction_wheel_pos, const double left_traction_wheel_pos,
80 const double steer_pos, const double dt);
81
92 const double right_traction_wheel_pos, const double left_traction_wheel_pos,
93 const double right_steer_pos, const double left_steer_pos, const double dt);
94
103 const double traction_wheel_vel, const double steer_pos, const double dt);
104
114 const double right_traction_wheel_vel, const double left_traction_wheel_vel,
115 const double steer_pos, const double dt);
116
127 const double right_traction_wheel_vel, const double left_traction_wheel_vel,
128 const double right_steer_pos, const double left_steer_pos, const double dt);
129
136 void update_open_loop(const double v_bx, const double omega_bz, const double dt);
137
142 void set_odometry_type(const unsigned int type);
143
148 double get_heading() const { return heading_; }
149
154 double get_x() const { return x_; }
155
160 double get_y() const { return y_; }
161
166 double get_linear() const { return linear_; }
167
172 double get_angular() const { return angular_; }
173
177 void set_wheel_params(
178 const double wheel_radius, const double wheelbase = 0.0, const double wheel_track = 0.0);
179
184 void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size);
185
193 std::tuple<std::vector<double>, std::vector<double>> get_commands(
194 const double v_bx, const double omega_bz, const bool open_loop = true);
195
199 void reset_odometry();
200
201private:
208 bool update_odometry(const double v_bx, const double omega_bz, const double dt);
209
216 void integrate_runge_kutta_2(const double v_bx, const double omega_bz, const double dt);
217
224 void integrate_fk(const double v_bx, const double omega_bz, const double dt);
225
231 double convert_twist_to_steering_angle(const double v_bx, const double omega_bz);
232
239 double get_linear_velocity_double_traction_axle(
240 const double right_traction_wheel_vel, const double left_traction_wheel_vel,
241 const double steer_pos);
242
246 void reset_accumulators();
247
249 rclcpp::Time timestamp_;
250
252 double x_; // [m]
253 double y_; // [m]
254 double steer_pos_; // [rad]
255 double heading_; // [rad]
256
258 double linear_; // [m/s]
259 double angular_; // [rad/s]
260
262 double wheel_track_; // [m]
263 double wheelbase_; // [m]
264 double wheel_radius_; // [m]
265
267 int config_type_ = -1;
268
270 double traction_wheel_old_pos_;
271 double traction_right_wheel_old_pos_;
272 double traction_left_wheel_old_pos_;
274 size_t velocity_rolling_window_size_;
275 rcpputils::RollingMeanAccumulator<double> linear_acc_;
276 rcpputils::RollingMeanAccumulator<double> angular_acc_;
277};
278} // namespace steering_odometry
279
280#endif // STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition steering_odometry.hpp:43
double get_heading() const
heading getter
Definition steering_odometry.hpp:148
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:76
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:194
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:217
double get_linear() const
linear velocity getter
Definition steering_odometry.hpp:166
double get_angular() const
angular velocity getter
Definition steering_odometry.hpp:172
double get_x() const
x position getter
Definition steering_odometry.hpp:154
void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size)
Velocity rolling window size setter.
Definition steering_odometry.cpp:201
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:184
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:122
double get_y() const
y position getter
Definition steering_odometry.hpp:160
void reset_odometry()
Reset poses, heading, and accumulators.
Definition steering_odometry.cpp:308
void init(const rclcpp::Time &time)
Initialize the odometry.
Definition steering_odometry.cpp:47
void set_odometry_type(const unsigned int type)
Set odometry type.
Definition steering_odometry.cpp:208