Go to the documentation of this file.
17 #ifndef IGNITION_MATH_DIFFDRIVEODOMETRY_HH_
18 #define IGNITION_MATH_DIFFDRIVEODOMETRY_HH_
23 #include <ignition/math/Export.hh>
24 #include <ignition/math/config.hh>
34 inline namespace IGNITION_MATH_VERSION_NAMESPACE {
37 class DiffDriveOdometryPrivate;
93 public:
void Init(
const clock::time_point &_time);
97 public:
bool Initialized()
const;
105 public:
bool Update(
const Angle &_leftPos,
const Angle &_rightPos,
106 const clock::time_point &_time);
110 public:
const Angle &Heading()
const;
114 public:
double X()
const;
118 public:
double Y()
const;
122 public:
double LinearVelocity()
const;
126 public:
const Angle &AngularVelocity()
const;
132 public:
void SetWheelParams(
double _wheelSeparation,
133 double _leftWheelRadius,
double _rightWheelRadius);
137 public:
void SetVelocityRollingWindowSize(
size_t _size);
142 #pragma warning(push)
143 #pragma warning(disable: 4251)
Definition: AdditivelySeparableScalarField3.hh:27
const Angle & Heading() const
Get the heading.
~DiffDriveOdometry()
Destructor.
void SetWheelParams(double _wheelSeparation, double _leftWheelRadius, double _rightWheelRadius)
Set the wheel parameters including the radius and separation.
Computes odometry values based on a set of kinematic properties and wheel speeds for a diff-drive veh...
Definition: DiffDriveOdometry.hh:81
double Y() const
Get the Y position.
void Init(const clock::time_point &_time)
Initialize the odometry.
DiffDriveOdometry(size_t _windowSize=10)
Constructor.
double X() const
Get the X position.
bool Initialized() const
Get whether Init has been called.
const Angle & AngularVelocity() const
Get the angular velocity.
double LinearVelocity() const
Get the linear velocity.
The Angle class is used to simplify and clarify the use of radians and degrees measurements....
Definition: Angle.hh:61
bool Update(const Angle &_leftPos, const Angle &_rightPos, const clock::time_point &_time)
Updates the odometry class with latest wheels and steerings position.
void SetVelocityRollingWindowSize(size_t _size)
Set the velocity rolling window size.