Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
diff_drive_controller::Odometry Class Reference

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

#include <odometry.h>

List of all members.

Public Types

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

Public Member Functions

double getAngularEstimated () const
 Retrieves the angular velocity estimation.
double getHeading () const
 heading getter
double getLinearEstimated () const
 Retrieves the linear velocity estimation.
ros::Time getTimestamp () const
 timestamp getter
double getX () const
 x position getter
double getY () const
 y position getter
 Odometry (size_t velocity_rolling_window_size=10)
 Constructor Timestamp will get the current time value Value will be set to zero.
void setWheelParams (double wheel_separation, double wheel_radius)
 Sets the wheel parameters: radius and separation.
bool update (double left_pos, double right_pos, const ros::Time &time)
 Updates the odometry class with latest wheels position.

Private Types

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

Private Member Functions

void integrateExact (double linear, double angular)
 Integrates the velocities (linear and angular) using exact method.
void integrateRungeKutta2 (double linear, double angular)
 Integrates the velocities (linear and angular) using 2nd order Runge-Kutta.

Private Attributes

RollingMeanAcc angular_acc_
double heading_
IntegrationFunction integrate_fun_
 Integration funcion, used to integrate the odometry:
double left_wheel_old_pos_
 Previou wheel position/state [rad]:
RollingMeanAcc linear_acc_
 Rolling meand accumulators for the linar and angular velocities:
double right_wheel_old_pos_
ros::Time timestamp_
 Current timestamp:
double wheel_radius_
double wheel_separation_
 Wheel kinematic parameters [m]:
double x_
 Current pose:
double y_

Detailed Description

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

Definition at line 57 of file odometry.h.


Member Typedef Documentation

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

Integration function, used to integrate the odometry:

Definition at line 62 of file odometry.h.

typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> > diff_drive_controller::Odometry::RollingMeanAcc [private]

Rolling mean accumulator and window:

Definition at line 139 of file odometry.h.

typedef bacc::tag::rolling_window diff_drive_controller::Odometry::RollingWindow [private]

Definition at line 140 of file odometry.h.


Constructor & Destructor Documentation

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 48 of file odometry.cpp.


Member Function Documentation

Retrieves the angular velocity estimation.

Returns:
Rolling mean estimation of the angular velocity [rad/s]

Definition at line 103 of file odometry.cpp.

heading getter

Returns:
heading [rad]

Definition at line 85 of file odometry.h.

Retrieves the linear velocity estimation.

Returns:
Rolling mean estimation of the linear velocity [m]

Definition at line 98 of file odometry.cpp.

timestamp getter

Returns:
timestamp

Definition at line 112 of file odometry.h.

double diff_drive_controller::Odometry::getX ( ) const [inline]

x position getter

Returns:
x position [m]

Definition at line 94 of file odometry.h.

double diff_drive_controller::Odometry::getY ( ) const [inline]

y position getter

Returns:
y positioin [m]

Definition at line 103 of file odometry.h.

void diff_drive_controller::Odometry::integrateExact ( double  linear,
double  angular 
) [private]

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

Other possible integration method provided by the class.

Parameters:
linearLinear velocity [m] (linear displacement, i.e. m/s * dt) computed by encoders
angularAngular velocity [rad] (angular displacement, i.e. m/s * dt) computed by encoders
linear
angular

Exact integration (should solve problems when angular is zero):

Definition at line 132 of file odometry.cpp.

void diff_drive_controller::Odometry::integrateRungeKutta2 ( double  linear,
double  angular 
) [private]

Integrates the velocities (linear and angular) using 2nd order Runge-Kutta.

Parameters:
linearLinear velocity [m] (linear displacement, i.e. m/s * dt) computed by encoders
angularAngular velocity [rad] (angular displacement, i.e. m/s * dt) computed by encoders

Runge-Kutta 2nd order integration:

Normalization of angle to [-Pi, Pi]:

Definition at line 114 of file odometry.cpp.

void diff_drive_controller::Odometry::setWheelParams ( double  wheel_separation,
double  wheel_radius 
)

Sets the wheel parameters: radius and separation.

Parameters:
wheel_separationSeperation between left and right wheels [m]
wheel_radiusWheel radius [m]

Definition at line 108 of file odometry.cpp.

bool diff_drive_controller::Odometry::update ( double  left_pos,
double  right_pos,
const ros::Time time 
)

Updates the odometry class with latest wheels position.

Parameters:
left_posLeft wheel position [rad]
right_posRight wheel position [rad]
timeCurrent time
Returns:
true if the odometry is actually updated

Get current wheel joint positions:

Estimate velocity of wheels using old and current position:

Update old position with current:

Compute linear and angular diff:

Integrate odometry:

We cannot estimate the speed with very small time intervals:

Estimate speeds using a rolling mean to filter them out:

Definition at line 63 of file odometry.cpp.


Member Data Documentation

Definition at line 174 of file odometry.h.

Definition at line 162 of file odometry.h.

Integration funcion, used to integrate the odometry:

Definition at line 177 of file odometry.h.

Previou wheel position/state [rad]:

Definition at line 169 of file odometry.h.

Rolling meand accumulators for the linar and angular velocities:

Definition at line 173 of file odometry.h.

Definition at line 170 of file odometry.h.

Current timestamp:

Definition at line 157 of file odometry.h.

Definition at line 166 of file odometry.h.

Wheel kinematic parameters [m]:

Definition at line 165 of file odometry.h.

Current pose:

Definition at line 160 of file odometry.h.

Definition at line 161 of file odometry.h.


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


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri Aug 28 2015 12:36:52