Computes odometry values based on a set of kinematic properties and wheel speeds for a diff-drive vehicle. More...
#include <gz/math/DiffDriveOdometry.hh>
Public Member Functions | |
DiffDriveOdometry (size_t _windowSize=10) | |
Constructor. More... | |
const Angle & | AngularVelocity () const |
Get the angular velocity. More... | |
const Angle & | Heading () const |
Get the heading. More... | |
void | Init (const clock::time_point &_time) |
Initialize the odometry. More... | |
bool | Initialized () const |
Get whether Init has been called. More... | |
double | LinearVelocity () const |
Get the linear velocity. More... | |
void | SetVelocityRollingWindowSize (size_t _size) |
Set the velocity rolling window size. More... | |
void | SetWheelParams (double _wheelSeparation, double _leftWheelRadius, double _rightWheelRadius) |
Set the wheel parameters including the radius and separation. More... | |
bool | Update (const Angle &_leftPos, const Angle &_rightPos, const clock::time_point &_time) |
Updates the odometry class with latest wheels and steerings position. More... | |
double | X () const |
Get the X position. More... | |
double | Y () const |
Get the Y position. More... | |
Detailed Description
Computes odometry values based on a set of kinematic properties and wheel speeds for a diff-drive vehicle.
A vehicle with a heading of zero degrees has a local reference frame according to the diagram below.
Y ^ | | O--->X(forward)
Rotating the right wheel while keeping the left wheel fixed will cause the vehicle to rotate counter-clockwise. For example (excuse the lack of precision with ASCII art):
Y X(forward) ^ ^ \ / \ / O
Example Usage
Constructor & Destructor Documentation
◆ DiffDriveOdometry()
|
explicit |
Constructor.
- Parameters
-
[in] _windowSize Rolling window size used to compute the velocity mean
Member Function Documentation
◆ AngularVelocity()
const Angle& AngularVelocity | ( | ) | const |
Get the angular velocity.
- Returns
- The angular velocity in radian/second.
◆ Heading()
const Angle& Heading | ( | ) | const |
Get the heading.
- Returns
- The heading in radians.
◆ Init()
void Init | ( | const clock::time_point & | _time | ) |
Initialize the odometry.
- Parameters
-
[in] _time Current time.
◆ Initialized()
bool Initialized | ( | ) | const |
Get whether Init has been called.
- Returns
- True if Init has been called, false otherwise.
◆ LinearVelocity()
double LinearVelocity | ( | ) | const |
Get the linear velocity.
- Returns
- The linear velocity in meter/second.
◆ SetVelocityRollingWindowSize()
void SetVelocityRollingWindowSize | ( | size_t | _size | ) |
Set the velocity rolling window size.
- Parameters
-
[in] _size The Velocity rolling window size.
◆ SetWheelParams()
void SetWheelParams | ( | double | _wheelSeparation, |
double | _leftWheelRadius, | ||
double | _rightWheelRadius | ||
) |
Set the wheel parameters including the radius and separation.
- Parameters
-
[in] _wheelSeparation Distance between left and right wheels. [in] _leftWheelRadius Radius of the left wheel. [in] _rightWheelRadius Radius of the right wheel.
◆ Update()
Updates the odometry class with latest wheels and steerings position.
- Parameters
-
[in] _leftPos Left wheel position in radians. [in] _rightPos Right wheel postion in radians. [in] _time Current time point.
- Returns
- True if the odometry is actually updated.
◆ X()
double X | ( | ) | const |
Get the X position.
- Returns
- The X position in meters
◆ Y()
double Y | ( | ) | const |
Get the Y position.
- Returns
- The Y position in meters.
The documentation for this class was generated from the following file: