Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
ackermann_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 track, double front_wheel_radius, double rear_wheel_radius, double wheel_base)
 Sets the wheel parameters: radius and separation.
bool update (double front_wheel_angular_pos, double front_wheel_angular_vel, double rear_wheel_angular_pos, double rear_wheel_angular_vel, double front_steering, const ros::Time &time)
 Updates the odometry class with latest wheels and steering 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 front_wheel_radius_
double heading_
ros::Time last_update_timestamp_
double left_wheel_old_pos_
 Previou wheel position/state [rad]:
double linear_
 Current velocity:
RollingMeanAcc linear_acc_
double rear_wheel_radius_
double right_wheel_old_pos_
ros::Time timestamp_
 Current timestamp:
double track_
 Wheel kinematic parameters [m]:
size_t velocity_rolling_window_size_
 Rolling mean accumulators for the linar and angular velocities:
double wheel_base_
double wheel_old_pos_
double x_
 Current pose:
double y_

Detailed Description

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

Definition at line 19 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 24 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 9 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 102 of file odometry.h.

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

heading getter

Returns:
heading [rad]

Definition at line 66 of file odometry.h.

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

linear velocity getter

Returns:
linear velocity [m/s]

Definition at line 93 of file odometry.h.

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

x position getter

Returns:
x position [m]

Definition at line 75 of file odometry.h.

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

y position getter

Returns:
y position [m]

Definition at line 84 of file odometry.h.

Initialize the odometry.

Parameters:
timeCurrent time

Definition at line 30 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] (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 107 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] (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 92 of file odometry.cpp.

Reset linear and angular accumulators.

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

void ackermann_controller::Odometry::setWheelParams ( double  track,
double  front_wheel_radius,
double  rear_wheel_radius,
double  wheel_base 
)

Sets the wheel parameters: radius and separation.

Parameters:
trackSeperation between left and right wheels [m]
front_wheel_radiusWheel radius [m]
rear_wheel_radiusWheel radius [m]
wheel_baseWheel base [m]

Definition at line 77 of file odometry.cpp.

bool ackermann_controller::Odometry::update ( double  front_wheel_angular_pos,
double  front_wheel_angular_vel,
double  rear_wheel_angular_pos,
double  rear_wheel_angular_vel,
double  front_steering,
const ros::Time time 
)

Updates the odometry class with latest wheels and steering position.

Parameters:
front_wheel_angular_posFront wheel position [rad]
front_wheel_angular_velFront wheel angular speed [rad/s]
rear_wheel_angular_posRear wheel position [rad]
rear_wheel_angular_velRear wheel angular speed [rad/s]
front_steeringposition [rad]
timeROS time
Returns:
true if the odometry is actually updated

Get current wheel joint positions:

Estimate pos evolution of wheels using old and current position:

Update old position with current:

Integrate odometry:

Compute x, y and heading using velocity

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


Member Data Documentation

Definition at line 157 of file odometry.h.

Definition at line 172 of file odometry.h.

Definition at line 161 of file odometry.h.

Definition at line 153 of file odometry.h.

Definition at line 148 of file odometry.h.

Previou wheel position/state [rad]:

Definition at line 165 of file odometry.h.

Current velocity:

Definition at line 156 of file odometry.h.

Definition at line 171 of file odometry.h.

Definition at line 161 of file odometry.h.

Definition at line 166 of file odometry.h.

Current timestamp:

Definition at line 148 of file odometry.h.

Wheel kinematic parameters [m]:

Definition at line 160 of file odometry.h.

Rolling mean accumulators for the linar and angular velocities:

Definition at line 170 of file odometry.h.

Definition at line 162 of file odometry.h.

Definition at line 167 of file odometry.h.

Current pose:

Definition at line 151 of file odometry.h.

Definition at line 152 of file odometry.h.


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


ackermann_controller
Author(s): Vincent Rousseau
autogenerated on Sat Jun 8 2019 20:06:19