Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
ackermann_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 setVelocityRollingWindowSize (size_t velocity_rolling_window_size)
 Velocity rolling window size setter. More...
 
void setWheelbase (double wheelbase)
 
bool update (const std::vector< ActuatedJoint > &steering_joints, const std::vector< Wheel > &odometry_joints, 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...
 
void integrateRungeKutta2 (double linear, double angular)
 Integrates the velocities (linear and angular) using 2nd order Runge-Kutta. More...
 
void resetAccumulators ()
 Reset linear and angular accumulators. More...
 

Private Attributes

double angular_
 
RollingMeanAcc angular_acc_
 
double heading_
 
IntegrationFunction integrate_fun_
 Integration funcion, used to integrate the odometry: More...
 
double linear_
 Current velocity: More...
 
RollingMeanAcc linear_acc_
 
ros::Time timestamp_
 Current timestamp: More...
 
size_t velocity_rolling_window_size_
 Rolling mean accumulators for the linar and angular velocities: More...
 
double wheelbase_
 
std::map< std::string, double > wheels_old_pos_
 Previou wheel position/state [rad]: More...
 
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 27 of file odometry.h.

Member Typedef Documentation

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

Integration function, used to integrate the odometry:

Definition at line 32 of file odometry.h.

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

Rolling mean accumulator and window:

Definition at line 125 of file odometry.h.

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

Definition at line 126 of file odometry.h.

Constructor & Destructor Documentation

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

Member Function Documentation

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

angular velocity getter

Returns
angular velocity [rad/s]

Definition at line 106 of file odometry.h.

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

heading getter

Returns
heading [rad]

Definition at line 70 of file odometry.h.

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

linear velocity getter

Returns
linear velocity [m/s]

Definition at line 97 of file odometry.h.

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

x position getter

Returns
x position [m]

Definition at line 79 of file odometry.h.

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

y position getter

Returns
y position [m]

Definition at line 88 of file odometry.h.

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

Initialize the odometry.

Parameters
timeCurrent time

Definition at line 32 of file odometry.cpp.

void ackermann_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 computed by encoders
angularAngular velocity rad computed by encoders
linearlinear speed
angularangular speed

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

Definition at line 132 of file odometry.cpp.

void ackermann_controller::Odometry::integrateRungeKutta2 ( double  linear,
double  angular 
)
private

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

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

Runge-Kutta 2nd order integration:

Definition at line 117 of file odometry.cpp.

void ackermann_controller::Odometry::resetAccumulators ( )
private

Reset linear and angular accumulators.

Definition at line 147 of file odometry.cpp.

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

void ackermann_controller::Odometry::setWheelbase ( double  wheelbase)
inline

Definition at line 111 of file odometry.h.

bool ackermann_controller::Odometry::update ( const std::vector< ActuatedJoint > &  steering_joints,
const std::vector< Wheel > &  odometry_joints,
const ros::Time time 
)

Updates the odometry class with latest wheels position.

Parameters
timeCurrent time
Returns
true if the odometry is actually updated

Integrate odometry:

Estimate speeds using a rolling mean to filter them out:

Definition at line 39 of file odometry.cpp.

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

Member Data Documentation

double ackermann_controller::Odometry::angular_
private

Definition at line 157 of file odometry.h.

RollingMeanAcc ackermann_controller::Odometry::angular_acc_
private

Definition at line 167 of file odometry.h.

double ackermann_controller::Odometry::heading_
private

Definition at line 153 of file odometry.h.

IntegrationFunction ackermann_controller::Odometry::integrate_fun_
private

Integration funcion, used to integrate the odometry:

Definition at line 170 of file odometry.h.

double ackermann_controller::Odometry::linear_
private

Current velocity:

Definition at line 156 of file odometry.h.

RollingMeanAcc ackermann_controller::Odometry::linear_acc_
private

Definition at line 166 of file odometry.h.

ros::Time ackermann_controller::Odometry::timestamp_
private

Current timestamp:

Definition at line 148 of file odometry.h.

size_t ackermann_controller::Odometry::velocity_rolling_window_size_
private

Rolling mean accumulators for the linar and angular velocities:

Definition at line 165 of file odometry.h.

double ackermann_controller::Odometry::wheelbase_
private

Definition at line 159 of file odometry.h.

std::map<std::string, double> ackermann_controller::Odometry::wheels_old_pos_
private

Previou wheel position/state [rad]:

Definition at line 162 of file odometry.h.

double ackermann_controller::Odometry::x_
private

Current pose:

Definition at line 151 of file odometry.h.

double ackermann_controller::Odometry::y_
private

Definition at line 152 of file odometry.h.


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


ackermann_controller
Author(s): GĂ©rald Lelong
autogenerated on Mon Jun 10 2019 12:44:49