ros2_control - jazzy
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 <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
34namespace steering_odometry
35{
36const unsigned int BICYCLE_CONFIG = 0;
37const unsigned int TRICYCLE_CONFIG = 1;
38const unsigned int ACKERMANN_CONFIG = 2;
39
40inline bool is_close_to_zero(double val) { return std::fabs(val) < 1e-6; }
41
47{
48public:
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 unsigned int get_odometry_type() const { return static_cast<unsigned int>(config_type_); }
153
158 double get_heading() const { return heading_; }
159
164 double get_x() const { return x_; }
165
170 double get_y() const { return y_; }
171
176 double get_linear() const { return linear_; }
177
182 double get_angular() const { return angular_; }
183
187 void set_wheel_params(
188 const double wheel_radius, const double wheel_base = 0.0, const double wheel_track = 0.0);
189
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
201 void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size);
202
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
219 void reset_odometry();
220
221private:
228 bool update_odometry(const double v_bx, const double omega_bz, const double dt);
229
236 void integrate_runge_kutta_2(const double v_bx, const double omega_bz, const double dt);
237
244 void integrate_fk(const double v_bx, const double omega_bz, const double dt);
245
251 double convert_twist_to_steering_angle(const double v_bx, const double omega_bz);
252
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
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
276 rclcpp::Time timestamp_;
277
279 double x_; // [m]
280 double y_; // [m]
281 double steer_pos_; // [rad]
282 double heading_; // [rad]
283
285 double linear_; // [m/s]
286 double angular_; // [rad/s]
287
289 double wheel_track_traction_; // [m]
290 double wheel_track_steering_; // [m]
291 double wheel_base_; // [m]
292 double wheel_radius_; // [m]
293
295 int config_type_ = -1;
296
298 double traction_wheel_old_pos_;
299 double traction_right_wheel_old_pos_;
300 double traction_left_wheel_old_pos_;
302 size_t velocity_rolling_window_size_;
303 RollingMeanAccumulator linear_acc_;
304 RollingMeanAccumulator angular_acc_;
305};
306} // namespace steering_odometry
307
308#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:158
std::tuple< std::vector< double >, std::vector< double > > get_commands(const double v_bx, const double omega_bz, const bool open_loop=true, const bool reduce_wheel_speed_until_steering_reached=false)
Calculates inverse kinematics for the desired linear and angular velocities.
Definition steering_odometry.cpp:234
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:78
double get_linear() const
linear velocity getter
Definition steering_odometry.hpp:176
unsigned int get_odometry_type() const
Get odometry type.
Definition steering_odometry.hpp:152
double get_angular() const
angular velocity getter
Definition steering_odometry.hpp:182
double get_x() const
x position getter
Definition steering_odometry.hpp:164
void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size)
Velocity rolling window size setter.
Definition steering_odometry.cpp:215
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:188
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:124
void set_wheel_params(const double wheel_radius, const double wheel_base=0.0, const double wheel_track=0.0)
Sets the wheel parameters: radius, wheel_base, and wheel_track.
Definition steering_odometry.cpp:198
double get_y() const
y position getter
Definition steering_odometry.hpp:170
void reset_odometry()
Reset poses, heading, and accumulators.
Definition steering_odometry.cpp:349
void init(const rclcpp::Time &time)
Initialize the odometry.
Definition steering_odometry.cpp:49
void set_odometry_type(const unsigned int type)
Set odometry type.
Definition steering_odometry.cpp:222