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 getAngular () const
 angular velocity getter
double getHeading () const
 heading getter
double getLinear () const
 linear velocity getter
double getX () const
 x position getter
double getY () const
 y position getter
void init (const ros::Time &time)
 Initialize the odometry.
 Odometry (size_t velocity_rolling_window_size=10)
 Constructor Timestamp will get the current time value Value will be set to zero.
void setVelocityRollingWindowSize (size_t velocity_rolling_window_size)
 Velocity rolling window size setter.
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.
void updateOpenLoop (double linear, double angular, const ros::Time &time)
 Updates the odometry class with latest velocity command.

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.
void resetAccumulators ()
 Reset linear and angular accumulators.

Private Attributes

double angular_
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]:
double linear_
 Current velocity:
RollingMeanAcc linear_acc_
double right_wheel_old_pos_
ros::Time timestamp_
 Current timestamp:
size_t velocity_rolling_window_size_
 Rolling mean accumulators for the linar and angular velocities:
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 59 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 64 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 158 of file odometry.h.

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

Definition at line 159 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 50 of file odometry.cpp.


Member Function Documentation

angular velocity getter

Returns:
angular velocity [rad/s]

Definition at line 137 of file odometry.h.

heading getter

Returns:
heading [rad]

Definition at line 101 of file odometry.h.

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

linear velocity getter

Returns:
linear velocity [m/s]

Definition at line 128 of file odometry.h.

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

x position getter

Returns:
x position [m]

Definition at line 110 of file odometry.h.

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

y position getter

Returns:
y position [m]

Definition at line 119 of file odometry.h.

Initialize the odometry.

Parameters:
timeCurrent time

Definition at line 68 of file odometry.cpp.

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 153 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:

Definition at line 138 of file odometry.cpp.

Reset linear and angular accumulators.

Definition at line 168 of file odometry.cpp.

void diff_drive_controller::Odometry::setVelocityRollingWindowSize ( size_t  velocity_rolling_window_size)

Velocity rolling window size setter.

Parameters:
velocity_rolling_window_sizeVelocity rolling window size

Definition at line 131 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 125 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 75 of file odometry.cpp.

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


Member Data Documentation

Definition at line 190 of file odometry.h.

Definition at line 203 of file odometry.h.

Definition at line 186 of file odometry.h.

Integration funcion, used to integrate the odometry:

Definition at line 206 of file odometry.h.

Previou wheel position/state [rad]:

Definition at line 197 of file odometry.h.

Current velocity:

Definition at line 189 of file odometry.h.

Definition at line 202 of file odometry.h.

Definition at line 198 of file odometry.h.

Current timestamp:

Definition at line 181 of file odometry.h.

Rolling mean accumulators for the linar and angular velocities:

Definition at line 201 of file odometry.h.

Definition at line 194 of file odometry.h.

Wheel kinematic parameters [m]:

Definition at line 193 of file odometry.h.

Current pose:

Definition at line 184 of file odometry.h.

Definition at line 185 of file odometry.h.


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


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Sat Aug 13 2016 04:20:35