The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
More...
#include <odometry.hpp>
|
typedef std::function< void(double, double, double)> | IntegrationFunction |
| Integration function, used to integrate the odometry:
|
|
|
| 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. More...
|
|
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. More...
|
|
double | getX () const |
|
double | getY () const |
|
double | getRz () const |
|
double | getVx () const |
|
double | getVy () const |
|
double | getWz () const |
|
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. More...
|
|
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
◆ getRz()
double mecanum_drive_controller::Odometry::getRz |
( |
| ) |
const |
|
inline |
- Returns
- orientation (z component) [m]
◆ getVx()
double mecanum_drive_controller::Odometry::getVx |
( |
| ) |
const |
|
inline |
- Returns
- body velocity of the base frame (linear x component) [m/s]
◆ getVy()
double mecanum_drive_controller::Odometry::getVy |
( |
| ) |
const |
|
inline |
- Returns
- body velocity of the base frame (linear y component) [m/s]
◆ getWz()
double mecanum_drive_controller::Odometry::getWz |
( |
| ) |
const |
|
inline |
- Returns
- body velocity of the base frame (angular z component) [m/s]
◆ getX()
double mecanum_drive_controller::Odometry::getX |
( |
| ) |
const |
|
inline |
- Returns
- position (x component) [m]
◆ getY()
double mecanum_drive_controller::Odometry::getY |
( |
| ) |
const |
|
inline |
- Returns
- position (y component) [m]
◆ init()
void mecanum_drive_controller::Odometry::init |
( |
const rclcpp::Time & |
time, |
|
|
std::array< double, PLANAR_POINT_DIM > |
base_frame_offset |
|
) |
| |
Initialize the odometry.
- Parameters
-
◆ setWheelsParams()
void mecanum_drive_controller::Odometry::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] |
◆ update()
bool mecanum_drive_controller::Odometry::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
We cannot estimate the speed with very small time intervals:
Compute FK (i.e. compute mobile robot's body twist out of its wheels velocities): NOTE: the mecanum IK gives the body speed at the center frame, we then offset this velocity at the base frame. NOTE: in the diff drive the velocity is filtered out, but we prefer to return it raw and let the user perform post-processing at will. We prefer this way of doing as filtering introduces delay (which makes it difficult to interpret and compare behavior curves).
- Note
- The variables meaning: angular_transformation_from_center_2_base: Rotation transformation matrix, to transform from center frame to base frame linear_transformation_from_center_2_base: offset/linear transformation matrix, to transform from center frame to base frame
Integration. NOTE: the position is expressed in the odometry frame , unlike the twist which is expressed in the body frame.
The documentation for this class was generated from the following files:
- ros2_controllers/mecanum_drive_controller/include/mecanum_drive_controller/odometry.hpp
- ros2_controllers/mecanum_drive_controller/src/odometry.cpp