Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
ackermann_steering_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 setWheelParams (double wheel_reparation_h, double wheel_radius)
 Sets the wheel parameters: radius and separation. More...
 
bool update (double rear_wheel_pos, double front_steer_pos, 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_
 
double rear_wheel_old_pos_
 Previous wheel position/state [rad]: More...
 
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_
 
double wheel_separation_h_
 Wheel kinematic parameters [m]: 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 60 of file odometry.h.

Member Typedef Documentation

typedef boost::function<void(double, double)> ackermann_steering_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> > ackermann_steering_controller::Odometry::RollingMeanAcc
private

Rolling mean accumulator and window:

Definition at line 159 of file odometry.h.

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

Definition at line 160 of file odometry.h.

Constructor & Destructor Documentation

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

Member Function Documentation

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

angular velocity getter

Returns
angular velocity [rad/s]

Definition at line 138 of file odometry.h.

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

heading getter

Returns
heading [rad]

Definition at line 102 of file odometry.h.

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

linear velocity getter

Returns
linear velocity [m/s]

Definition at line 129 of file odometry.h.

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

x position getter

Returns
x position [m]

Definition at line 111 of file odometry.h.

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

y position getter

Returns
y position [m]

Definition at line 120 of file odometry.h.

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

Initialize the odometry.

Parameters
timeCurrent time

Definition at line 68 of file odometry.cpp.

void ackermann_steering_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
linear
angular

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

Definition at line 154 of file odometry.cpp.

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

void ackermann_steering_controller::Odometry::resetAccumulators ( )
private

Reset linear and angular accumulators.

Definition at line 169 of file odometry.cpp.

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

void ackermann_steering_controller::Odometry::setWheelParams ( double  wheel_reparation_h,
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 126 of file odometry.cpp.

bool ackermann_steering_controller::Odometry::update ( double  rear_wheel_pos,
double  front_steer_pos,
const ros::Time time 
)

Updates the odometry class with latest wheels position.

Parameters
rear_wheel_posRear wheel position [rad]
front_steer_posFront Steer 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 ackermann_steering_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 114 of file odometry.cpp.

Member Data Documentation

double ackermann_steering_controller::Odometry::angular_
private

Definition at line 191 of file odometry.h.

RollingMeanAcc ackermann_steering_controller::Odometry::angular_acc_
private

Definition at line 203 of file odometry.h.

double ackermann_steering_controller::Odometry::heading_
private

Definition at line 187 of file odometry.h.

IntegrationFunction ackermann_steering_controller::Odometry::integrate_fun_
private

Integration funcion, used to integrate the odometry:

Definition at line 206 of file odometry.h.

double ackermann_steering_controller::Odometry::linear_
private

Current velocity:

Definition at line 190 of file odometry.h.

RollingMeanAcc ackermann_steering_controller::Odometry::linear_acc_
private

Definition at line 202 of file odometry.h.

double ackermann_steering_controller::Odometry::rear_wheel_old_pos_
private

Previous wheel position/state [rad]:

Definition at line 198 of file odometry.h.

ros::Time ackermann_steering_controller::Odometry::timestamp_
private

Current timestamp:

Definition at line 182 of file odometry.h.

size_t ackermann_steering_controller::Odometry::velocity_rolling_window_size_
private

Rolling mean accumulators for the linar and angular velocities:

Definition at line 201 of file odometry.h.

double ackermann_steering_controller::Odometry::wheel_radius_
private

Definition at line 195 of file odometry.h.

double ackermann_steering_controller::Odometry::wheel_separation_h_
private

Wheel kinematic parameters [m]:

Definition at line 194 of file odometry.h.

double ackermann_steering_controller::Odometry::x_
private

Current pose:

Definition at line 185 of file odometry.h.

double ackermann_steering_controller::Odometry::y_
private

Definition at line 186 of file odometry.h.


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


ackermann_steering_controller
Author(s): Masaru Morita
autogenerated on Sat Apr 18 2020 03:58:07