18#ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
19#define STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
25#include <rclcpp/time.hpp>
28#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
29#include "rcpputils/rolling_mean_accumulator.hpp"
31#include "rcppmath/rolling_mean_accumulator.hpp"
34namespace steering_odometry
36const unsigned int BICYCLE_CONFIG = 0;
37const unsigned int TRICYCLE_CONFIG = 1;
38const unsigned int ACKERMANN_CONFIG = 2;
40inline bool is_close_to_zero(
double val) {
return std::fabs(val) < 1e-6; }
62 void init(
const rclcpp::Time & time);
72 const double traction_wheel_pos,
const double steer_pos,
const double dt);
83 const double right_traction_wheel_pos,
const double left_traction_wheel_pos,
84 const double steer_pos,
const double dt);
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);
107 const double traction_wheel_vel,
const double steer_pos,
const double dt);
118 const double right_traction_wheel_vel,
const double left_traction_wheel_vel,
119 const double steer_pos,
const double dt);
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);
140 void update_open_loop(
const double v_bx,
const double omega_bz,
const double dt);
188 const double wheel_radius,
const double wheel_base = 0.0,
const double wheel_track = 0.0);
194 const double wheel_radius,
const double wheel_base,
const double wheel_track_steering,
195 const double wheel_track_traction);
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);
228 bool update_odometry(
const double v_bx,
const double omega_bz,
const double dt);
236 void integrate_runge_kutta_2(
const double v_bx,
const double omega_bz,
const double dt);
244 void integrate_fk(
const double v_bx,
const double omega_bz,
const double dt);
251 double convert_twist_to_steering_angle(
const double v_bx,
const double omega_bz);
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);
266 void reset_accumulators();
269#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
270 using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
272 using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
276 rclcpp::Time timestamp_;
289 double wheel_track_traction_;
290 double wheel_track_steering_;
292 double wheel_radius_;
295 int config_type_ = -1;
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_;
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