ros2_control - rolling
Public Member Functions | List of all members
steering_odometry::SteeringOdometry Class Reference

The Odometry class handles odometry readings (2D pose and velocity with related timestamp) More...

#include <steering_odometry.hpp>

Public Member Functions

 SteeringOdometry (size_t velocity_rolling_window_size=10)
 Constructor Timestamp will get the current time value Value will be set to zero. More...
 
void init (const rclcpp::Time &time)
 Initialize the odometry. More...
 
bool update_from_position (const double traction_wheel_pos, const double steer_pos, const double dt)
 Updates the odometry class with latest wheels position. More...
 
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. More...
 
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. More...
 
bool update_from_velocity (const double traction_wheel_vel, const double steer_pos, const double dt)
 Updates the odometry class with latest wheels position. More...
 
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. More...
 
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. More...
 
void update_open_loop (const double v_bx, const double omega_bz, const double dt)
 Updates the odometry class with latest velocity command. More...
 
void set_odometry_type (const unsigned int type)
 Set odometry type. More...
 
double get_heading () const
 heading getter More...
 
double get_x () const
 x position getter More...
 
double get_y () const
 y position getter More...
 
double get_linear () const
 linear velocity getter More...
 
double get_angular () const
 angular velocity getter More...
 
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. More...
 
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. More...
 
void reset_odometry ()
 Reset poses, heading, and accumulators.
 

Detailed Description

The Odometry class handles odometry readings (2D pose and velocity with related timestamp)

Constructor & Destructor Documentation

◆ SteeringOdometry()

steering_odometry::SteeringOdometry::SteeringOdometry ( size_t  velocity_rolling_window_size = 10)
explicit

Constructor Timestamp will get the current time value Value will be set to zero.

Parameters
velocity_rolling_window_sizeRolling window size used to compute the velocity mean

Member Function Documentation

◆ get_angular()

double steering_odometry::SteeringOdometry::get_angular ( ) const
inline

angular velocity getter

Returns
angular velocity [rad/s]

◆ get_commands()

std::tuple< std::vector< double >, std::vector< double > > steering_odometry::SteeringOdometry::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_bxDesired linear velocity of the robot in x_b-axis direction
omega_bzDesired angular velocity of the robot around x_z-axis
open_loopIf false, the IK will be calculated using measured steering angle
Returns
Tuple of velocity commands and steering commands

◆ get_heading()

double steering_odometry::SteeringOdometry::get_heading ( ) const
inline

heading getter

Returns
heading [rad]

◆ get_linear()

double steering_odometry::SteeringOdometry::get_linear ( ) const
inline

linear velocity getter

Returns
linear velocity [m/s]

◆ get_x()

double steering_odometry::SteeringOdometry::get_x ( ) const
inline

x position getter

Returns
x position [m]

◆ get_y()

double steering_odometry::SteeringOdometry::get_y ( ) const
inline

y position getter

Returns
y position [m]

◆ init()

void steering_odometry::SteeringOdometry::init ( const rclcpp::Time &  time)

Initialize the odometry.

Parameters
timeCurrent time

◆ set_odometry_type()

void steering_odometry::SteeringOdometry::set_odometry_type ( const unsigned int  type)

Set odometry type.

Parameters
typeodometry type

◆ set_velocity_rolling_window_size()

void steering_odometry::SteeringOdometry::set_velocity_rolling_window_size ( const size_t  velocity_rolling_window_size)

Velocity rolling window size setter.

Parameters
velocity_rolling_window_sizeVelocity rolling window size

◆ update_from_position() [1/3]

bool steering_odometry::SteeringOdometry::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_posRight traction wheel position [rad]
left_traction_wheel_posLeft traction wheel position [rad]
right_steer_posRight steer wheel position [rad]
left_steer_posLeft steer wheel position [rad]
dttime difference to last call
Returns
true if the odometry is actually updated

Update old position with current:

◆ update_from_position() [2/3]

bool steering_odometry::SteeringOdometry::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_posRight traction wheel velocity [rad]
left_traction_wheel_posLeft traction wheel velocity [rad]
steer_posSteer wheel position [rad]
dttime difference to last call
Returns
true if the odometry is actually updated

Update old position with current:

◆ update_from_position() [3/3]

bool steering_odometry::SteeringOdometry::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_postraction wheel position [rad]
steer_posSteer wheel position [rad]
dttime difference to last call
Returns
true if the odometry is actually updated

Update old position with current:

◆ update_from_velocity() [1/3]

bool steering_odometry::SteeringOdometry::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_velRight traction wheel velocity [rad/s]
left_traction_wheel_velLeft traction wheel velocity [rad/s]
right_steer_posRight steer wheel position [rad]
left_steer_posLeft steer wheel position [rad]
dttime difference to last call
Returns
true if the odometry is actually updated

◆ update_from_velocity() [2/3]

bool steering_odometry::SteeringOdometry::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_velRight traction wheel velocity [rad/s]
left_traction_wheel_velLeft traction wheel velocity [rad/s]
steer_posSteer wheel position [rad]
dttime difference to last call
Returns
true if the odometry is actually updated

◆ update_from_velocity() [3/3]

bool steering_odometry::SteeringOdometry::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_velTraction wheel velocity [rad/s]
steer_posSteer wheel position [rad]
dttime difference to last call
Returns
true if the odometry is actually updated

◆ update_open_loop()

void steering_odometry::SteeringOdometry::update_open_loop ( const double  v_bx,
const double  omega_bz,
const double  dt 
)

Updates the odometry class with latest velocity command.

Parameters
v_bxLinear velocity [m/s]
omega_bzAngular velocity [rad/s]
dttime difference to last call

Save last linear and angular velocity:

Integrate odometry:


The documentation for this class was generated from the following files: