Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
four_wheel_steering_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 norm
double getLinearX () const
 linear velocity getter along X on the robot base link frame
double getLinearY () const
 linear velocity getter along Y on the robot base link frame
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 wheel_radius, double wheel_base)
 Sets the wheel parameters: radius and separation.
bool update (const double &fl_speed, const double &fr_speed, const double &rl_speed, const double &rr_speed, double front_steering, double rear_steering, const ros::Time &time)
 Updates the odometry class with latest wheels and steerings 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 integrateXY (double linear_x, double linear_y, double angular)
 Integrates the velocities (linear on x and y and angular)
void resetAccumulators ()
 Reset linear and angular accumulators.

Private Attributes

double angular_
RollingMeanAcc angular_acc_
double heading_
ros::Time last_update_timestamp_
double linear_
 Current velocity:
RollingMeanAcc linear_acc_
double linear_x_
double linear_y_
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_
 Previous wheel position/state [rad]:
double wheel_radius_
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)> four_wheel_steering_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> > four_wheel_steering_controller::Odometry::RollingMeanAcc [private]

Rolling mean accumulator and window:

Definition at line 143 of file odometry.h.

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

Definition at line 144 of file odometry.h.


Constructor & Destructor Documentation

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


Member Function Documentation

angular velocity getter

Returns:
angular velocity [rad/s]

Definition at line 121 of file odometry.h.

heading getter

Returns:
heading [rad]

Definition at line 66 of file odometry.h.

linear velocity getter norm

Returns:
linear velocity [m/s]

Definition at line 94 of file odometry.h.

linear velocity getter along X on the robot base link frame

Returns:
linear velocity [m/s]

Definition at line 103 of file odometry.h.

linear velocity getter along Y on the robot base link frame

Returns:
linear velocity [m/s]

Definition at line 112 of file odometry.h.

x position getter

Returns:
x position [m]

Definition at line 75 of file odometry.h.

y position getter

Returns:
y position [m]

Definition at line 84 of file odometry.h.

Initialize the odometry.

Parameters:
timeCurrent time

Definition at line 29 of file odometry.cpp.

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

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

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

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

Definition at line 111 of file odometry.cpp.

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

void four_wheel_steering_controller::Odometry::integrateXY ( double  linear_x,
double  linear_y,
double  angular 
) [private]

Integrates the velocities (linear on x and y and angular)

Parameters:
linear_xLinear velocity along x of the robot frame [m] (linear displacement, i.e. m/s * dt) computed by encoders
linear_yLinear velocity along y of the robot frame [m] (linear displacement, i.e. m/s * dt) computed by encoders
angularAngular velocity [rad] (angular displacement, i.e. m/s * dt) computed by encoders

Definition at line 91 of file odometry.cpp.

Reset linear and angular accumulators.

Definition at line 126 of file odometry.cpp.

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

void four_wheel_steering_controller::Odometry::setWheelParams ( double  track,
double  wheel_radius,
double  wheel_base 
)

Sets the wheel parameters: radius and separation.

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

Definition at line 77 of file odometry.cpp.

bool four_wheel_steering_controller::Odometry::update ( const double &  fl_speed,
const double &  fr_speed,
const double &  rl_speed,
const double &  rr_speed,
double  front_steering,
double  rear_steering,
const ros::Time time 
)

Updates the odometry class with latest wheels and steerings position.

Parameters:
fl_speedfront left wheel vehicle speed [rad/s]
fr_speedfront right wheel vehicle speed [rad/s]
rl_speedrear left wheel vehicle speed [rad/s]
rr_speedrear right wheel vehicle speed [rad/s]
front_steeringsteering position [rad]
rear_steeringsteering position [rad]
timeCurrent time
Returns:
true if the odometry is actually updated

Compute x, y and heading using velocity

Integrate odometry:

Definition at line 37 of file odometry.cpp.

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


Member Data Documentation

Definition at line 183 of file odometry.h.

Definition at line 196 of file odometry.h.

Definition at line 179 of file odometry.h.

Definition at line 174 of file odometry.h.

Current velocity:

Definition at line 182 of file odometry.h.

Definition at line 195 of file odometry.h.

Definition at line 182 of file odometry.h.

Definition at line 182 of file odometry.h.

Current timestamp:

Definition at line 174 of file odometry.h.

Wheel kinematic parameters [m]:

Definition at line 186 of file odometry.h.

Rolling mean accumulators for the linar and angular velocities:

Definition at line 194 of file odometry.h.

Definition at line 188 of file odometry.h.

Previous wheel position/state [rad]:

Definition at line 191 of file odometry.h.

Definition at line 187 of file odometry.h.

Current pose:

Definition at line 177 of file odometry.h.

Definition at line 178 of file odometry.h.


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


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Sat Jun 8 2019 20:06:24