Class Odometry

Class Documentation

class Odometry

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

Public Types

typedef std::function<void(double, double, double)> IntegrationFunction

Integration function, used to integrate the odometry:

Public Functions

Odometry()

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

void init(const rclcpp::Time &time, std::array<double, PLANAR_POINT_DIM> base_frame_offset)

Initialize the odometry.

Parameters:

time – Current time

bool update(const double wheel_front_left_vel, const double wheel_rear_left_vel, const double wheel_rear_right_vel, const double wheel_front_right_vel, const double dt)

Updates the odometry class with latest wheels position.

Parameters:
  • wheel_front_left_vel – Wheel velocity [rad/s]

  • wheel_rear_left_vel – Wheel velocity [rad/s]

  • wheel_rear_right_vel – Wheel velocity [rad/s]

  • wheel_front_right_vel – Wheel velocity [rad/s]

  • time – Current time

Returns:

true if the odometry is actually updated

inline double getX() const
Returns:

position (x component) [m]

inline double getY() const
Returns:

position (y component) [m]

inline double getRz() const
Returns:

orientation (z component) [m]

inline double getVx() const
Returns:

body velocity of the base frame (linear x component) [m/s]

inline double getVy() const
Returns:

body velocity of the base frame (linear y component) [m/s]

inline double getWz() const
Returns:

body velocity of the base frame (angular z component) [m/s]

void setWheelsParams(const double sum_of_robot_center_projection_on_X_Y_axis, const double wheels_radius)

Sets the wheels parameters: mecanum geometric param and radius.

Parameters:
  • sum_of_robot_center_projection_on_X_Y_axis – Wheels geometric param (used in mecanum wheels’ ik) [m]

  • wheels_radius – Wheels radius [m]