Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
double_diff_drive_controller::Odometry Class Reference

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

#include <odometry.h>

Public Types

typedef boost::function< void(double, double)> IntegrationFunction
 Integration function, used to integrate the odometry: More...
 

Public Member Functions

double getAngular () const
 angular velocity getter More...
 
double getHeading () const
 heading getter More...
 
double getLinear () const
 linear velocity getter More...
 
double getX () const
 x position getter More...
 
double getY () const
 y position getter More...
 
void init (const ros::Time &time)
 Initialize the odometry. More...
 
 Odometry (size_t velocity_rolling_window_size=10)
 Constructor Timestamp will get the current time value Value will be set to zero. More...
 
void setGearRatios (double drive_motor_gear_ratio, double steer_motor_gear_ratio)
 Sets the gear ratio parameters: gear ratio. More...
 
void setWheelsParams (double wheel_radius, double wheel_separation)
 Sets the wheels parameters: radius and seperation. More...
 
bool update (double drive_motor_vel, double steer_motor_vel, const ros::Time &time)
 Updates the odometry class with latest wheels position. More...
 
void updateOpenLoop (double linear, double angular, const ros::Time &time)
 Updates the odometry class with latest velocity command. More...
 

Private Types

typedef bacc::accumulator_set< double, bacc::stats< bacc::tag::rolling_mean > > RollingMeanAcc
 Rolling mean accumulator and window: More...
 
typedef bacc::tag::rolling_window RollingWindow
 

Private Member Functions

void integrateExact (double linear, double angular)
 Integrates the velocities (linear and angular) using exact method. More...
 

Private Attributes

double angular_
 
RollingMeanAcc angular_acc_
 
double drive_motor_gear_ratio_
 
double heading_
 
IntegrationFunction integrate_fun_
 Integration funcion, used to integrate the odometry: More...
 
double linear_
 Current velocity: More...
 
RollingMeanAcc linear_acc_
 
double steer_motor_gear_ratio_
 
ros::Time timestamp_
 Current timestamp: More...
 
size_t velocity_rolling_window_size_
 Rolling mean accumulators for the linar and angular velocities: More...
 
double wheel_radius_
 Wheels kinematic parameters [m]: More...
 
double wheel_separation_
 
double x_
 Current pose: More...
 
double y_
 

Detailed Description

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

Definition at line 60 of file odometry.h.

Member Typedef Documentation

typedef boost::function<void(double, double)> double_diff_drive_controller::Odometry::IntegrationFunction

Integration function, used to integrate the odometry:

Definition at line 65 of file odometry.h.

typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> > double_diff_drive_controller::Odometry::RollingMeanAcc
private

Rolling mean accumulator and window:

Definition at line 160 of file odometry.h.

typedef bacc::tag::rolling_window double_diff_drive_controller::Odometry::RollingWindow
private

Definition at line 161 of file odometry.h.

Constructor & Destructor Documentation

double_diff_drive_controller::Odometry::Odometry ( size_t  velocity_rolling_window_size = 10)

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

Definition at line 54 of file odometry.cpp.

Member Function Documentation

double double_diff_drive_controller::Odometry::getAngular ( ) const
inline

angular velocity getter

Returns
angular velocity [rad/s]

Definition at line 138 of file odometry.h.

double double_diff_drive_controller::Odometry::getHeading ( ) const
inline

heading getter

Returns
heading [rad]

Definition at line 102 of file odometry.h.

double double_diff_drive_controller::Odometry::getLinear ( ) const
inline

linear velocity getter

Returns
linear velocity [m/s]

Definition at line 129 of file odometry.h.

double double_diff_drive_controller::Odometry::getX ( ) const
inline

x position getter

Returns
x position [m]

Definition at line 111 of file odometry.h.

double double_diff_drive_controller::Odometry::getY ( ) const
inline

y position getter

Returns
y position [m]

Definition at line 120 of file odometry.h.

void double_diff_drive_controller::Odometry::init ( const ros::Time time)

Initialize the odometry.

Parameters
timeCurrent time

Definition at line 71 of file odometry.cpp.

void double_diff_drive_controller::Odometry::integrateExact ( double  linear,
double  angular 
)
private

Integrates the velocities (linear and angular) using exact method.

Parameters
linearLinear velocity along X m computed by encoders
angularAngular velocity rad computed by encoders

Integrate angular velocity.

The odometry pose should be published in the /odom frame (unlike the odometry twist which is a body twist). Project the twist in the odometry basis (we cannot integrate linear, angular 'as are' because they correspond to a body twist).

Integrate linear velocity.

Definition at line 128 of file odometry.cpp.

void double_diff_drive_controller::Odometry::setGearRatios ( double  drive_motor_gear_ratio,
double  steer_motor_gear_ratio 
)

Sets the gear ratio parameters: gear ratio.

Parameters
drive_motor_gear_ratioDrive motor gear ratio [-]
steer_motor_gear_ratioSteer motor gear ratio [-]

Definition at line 121 of file odometry.cpp.

void double_diff_drive_controller::Odometry::setWheelsParams ( double  wheel_radius,
double  wheel_separation 
)

Sets the wheels parameters: radius and seperation.

Parameters
wheel_radiusWheels radius [m]
wheel_seperationDistance between wheels [m]

Definition at line 114 of file odometry.cpp.

bool double_diff_drive_controller::Odometry::update ( double  drive_motor_vel,
double  steer_motor_vel,
const ros::Time time 
)

Updates the odometry class with latest wheels position.

Parameters
wheel0_velWheel velocity [rad]
wheel1_velWheel velocity [rad]
timeCurrent time
Returns
true if the odometry is actually updated

We cannot estimate the speed with very small time intervals:

Integrate odometry.

Definition at line 82 of file odometry.cpp.

void double_diff_drive_controller::Odometry::updateOpenLoop ( double  linear,
double  angular,
const ros::Time time 
)

Updates the odometry class with latest velocity command.

Parameters
linearLinear velocity [m/s]
angularAngular velocity [rad/s]
timeCurrent time

Save last linear and angular velocity:

Integrate odometry:

Definition at line 101 of file odometry.cpp.

Member Data Documentation

double double_diff_drive_controller::Odometry::angular_
private

Definition at line 180 of file odometry.h.

RollingMeanAcc double_diff_drive_controller::Odometry::angular_acc_
private

Definition at line 189 of file odometry.h.

double double_diff_drive_controller::Odometry::drive_motor_gear_ratio_
private

Definition at line 184 of file odometry.h.

double double_diff_drive_controller::Odometry::heading_
private

Definition at line 176 of file odometry.h.

IntegrationFunction double_diff_drive_controller::Odometry::integrate_fun_
private

Integration funcion, used to integrate the odometry:

Definition at line 192 of file odometry.h.

double double_diff_drive_controller::Odometry::linear_
private

Current velocity:

Definition at line 179 of file odometry.h.

RollingMeanAcc double_diff_drive_controller::Odometry::linear_acc_
private

Definition at line 188 of file odometry.h.

double double_diff_drive_controller::Odometry::steer_motor_gear_ratio_
private

Definition at line 184 of file odometry.h.

ros::Time double_diff_drive_controller::Odometry::timestamp_
private

Current timestamp:

Definition at line 171 of file odometry.h.

size_t double_diff_drive_controller::Odometry::velocity_rolling_window_size_
private

Rolling mean accumulators for the linar and angular velocities:

Definition at line 187 of file odometry.h.

double double_diff_drive_controller::Odometry::wheel_radius_
private

Wheels kinematic parameters [m]:

Definition at line 183 of file odometry.h.

double double_diff_drive_controller::Odometry::wheel_separation_
private

Definition at line 183 of file odometry.h.

double double_diff_drive_controller::Odometry::x_
private

Current pose:

Definition at line 174 of file odometry.h.

double double_diff_drive_controller::Odometry::y_
private

Definition at line 175 of file odometry.h.


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


moose_control
Author(s): Tony Baltovski
autogenerated on Wed Mar 10 2021 03:43:55