Class SteeringOdometry
Defined in File steering_odometry.hpp
Class Documentation
-
class SteeringOdometry
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Public Functions
-
explicit SteeringOdometry(size_t velocity_rolling_window_size = 10)
Constructor Timestamp will get the current time value Value will be set to zero.
- Parameters:
velocity_rolling_window_size – Rolling window size used to compute the velocity mean
-
void init(const rclcpp::Time &time)
Initialize the odometry.
- Parameters:
time – Current time
-
bool update_from_position(const double traction_wheel_pos, const double steer_pos, const double dt)
Updates the odometry class with latest wheels position.
- Parameters:
traction_wheel_pos – traction wheel position [rad]
steer_pos – Steer wheel position [rad]
dt – time difference to last call
- Returns:
true if the odometry is actually updated
-
bool update_from_position(const double right_traction_wheel_pos, const double left_traction_wheel_pos, const double steer_pos, const double dt)
Updates the odometry class with latest wheels position.
- Parameters:
right_traction_wheel_pos – Right traction wheel velocity [rad]
left_traction_wheel_pos – Left traction wheel velocity [rad]
steer_pos – Steer wheel position [rad]
dt – time difference to last call
- Returns:
true if the odometry is actually updated
-
bool update_from_position(const double right_traction_wheel_pos, const double left_traction_wheel_pos, const double right_steer_pos, const double left_steer_pos, const double dt)
Updates the odometry class with latest wheels position.
- Parameters:
right_traction_wheel_pos – Right traction wheel position [rad]
left_traction_wheel_pos – Left traction wheel position [rad]
right_steer_pos – Right steer wheel position [rad]
left_steer_pos – Left steer wheel position [rad]
dt – time difference to last call
- Returns:
true if the odometry is actually updated
-
bool update_from_velocity(const double traction_wheel_vel, const double steer_pos, const double dt)
Updates the odometry class with latest wheels position.
- Parameters:
traction_wheel_vel – Traction wheel velocity [rad/s]
steer_pos – Steer wheel position [rad]
dt – time difference to last call
- Returns:
true if the odometry is actually updated
-
bool update_from_velocity(const double right_traction_wheel_vel, const double left_traction_wheel_vel, const double steer_pos, const double dt)
Updates the odometry class with latest wheels position.
- Parameters:
right_traction_wheel_vel – Right traction wheel velocity [rad/s]
left_traction_wheel_vel – Left traction wheel velocity [rad/s]
steer_pos – Steer wheel position [rad]
dt – time difference to last call
- Returns:
true if the odometry is actually updated
-
bool update_from_velocity(const double right_traction_wheel_vel, const double left_traction_wheel_vel, const double right_steer_pos, const double left_steer_pos, const double dt)
Updates the odometry class with latest wheels position.
- Parameters:
right_traction_wheel_vel – Right traction wheel velocity [rad/s]
left_traction_wheel_vel – Left traction wheel velocity [rad/s]
right_steer_pos – Right steer wheel position [rad]
left_steer_pos – Left steer wheel position [rad]
dt – time difference to last call
- Returns:
true if the odometry is actually updated
-
void update_open_loop(const double v_bx, const double omega_bz, const double dt)
Updates the odometry class with latest velocity command.
- Parameters:
v_bx – Linear velocity [m/s]
omega_bz – Angular velocity [rad/s]
dt – time difference to last call
-
void set_odometry_type(const unsigned int type)
Set odometry type.
- Parameters:
type – odometry type
-
inline double get_heading() const
heading getter
- Returns:
heading [rad]
-
inline double get_x() const
x position getter
- Returns:
x position [m]
-
inline double get_y() const
y position getter
- Returns:
y position [m]
-
inline double get_linear() const
linear velocity getter
- Returns:
linear velocity [m/s]
-
inline double get_angular() const
angular velocity getter
- Returns:
angular velocity [rad/s]
-
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.
-
void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size)
Velocity rolling window size setter.
- Parameters:
velocity_rolling_window_size – Velocity rolling window size
-
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.
- Parameters:
v_bx – Desired linear velocity of the robot in x_b-axis direction
omega_bz – Desired angular velocity of the robot around x_z-axis
open_loop – If false, the IK will be calculated using measured steering angle
- Returns:
Tuple of velocity commands and steering commands
-
void reset_odometry()
Reset poses, heading, and accumulators.
-
explicit SteeringOdometry(size_t velocity_rolling_window_size = 10)