18#ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
19#define STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
25#include "realtime_tools/realtime_buffer.h"
26#include "realtime_tools/realtime_publisher.h"
28#include "rcpputils/rolling_mean_accumulator.hpp"
30namespace steering_odometry
32const unsigned int BICYCLE_CONFIG = 0;
33const unsigned int TRICYCLE_CONFIG = 1;
34const unsigned int ACKERMANN_CONFIG = 2;
36inline bool is_close_to_zero(
double val) {
return std::fabs(val) < 1e-6; }
58 void init(
const rclcpp::Time & time);
68 const double traction_wheel_pos,
const double steer_pos,
const double dt);
79 const double right_traction_wheel_pos,
const double left_traction_wheel_pos,
80 const double steer_pos,
const double dt);
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);
103 const double traction_wheel_vel,
const double steer_pos,
const double dt);
114 const double right_traction_wheel_vel,
const double left_traction_wheel_vel,
115 const double steer_pos,
const double dt);
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);
136 void update_open_loop(
const double v_bx,
const double omega_bz,
const double dt);
178 const double wheel_radius,
const double wheelbase = 0.0,
const double wheel_track = 0.0);
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);
208 bool update_odometry(
const double v_bx,
const double omega_bz,
const double dt);
216 void integrate_runge_kutta_2(
const double v_bx,
const double omega_bz,
const double dt);
224 void integrate_fk(
const double v_bx,
const double omega_bz,
const double dt);
231 double convert_twist_to_steering_angle(
const double v_bx,
const double omega_bz);
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);
246 void reset_accumulators();
249 rclcpp::Time timestamp_;
264 double wheel_radius_;
267 int config_type_ = -1;
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_;
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