Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
four_wheel_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 getFrontSteerVel () const
 front steering velocity getter More...
 
double getHeading () const
 heading getter More...
 
double getLinear () const
 linear velocity getter norm More...
 
double getLinearAcceleration () const
 linear acceleration getter More...
 
double getLinearJerk () const
 linear jerk getter More...
 
double getLinearX () const
 linear velocity getter along X on the robot base link frame More...
 
double getLinearY () const
 linear velocity getter along Y on the robot base link frame More...
 
double getRearSteerVel () const
 rear steering 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 steering_track, double wheel_steering_y_offset, double wheel_radius, double wheel_base)
 Sets the wheel parameters: radius and separation. More...
 
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. 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 integrateXY (double linear_x, double linear_y, double angular)
 Integrates the velocities (linear on x and y and angular) More...
 
void resetAccumulators ()
 Reset linear and angular accumulators. More...
 

Private Attributes

double angular_
 
RollingMeanAcc front_steer_vel_acc_
 
double front_steer_vel_prev_
 
double heading_
 
ros::Time last_update_timestamp_
 Current timestamp: More...
 
double linear_
 Current velocity: More...
 
RollingMeanAcc linear_accel_acc_
 
double linear_accel_prev_
 
RollingMeanAcc linear_jerk_acc_
 
double linear_vel_prev_
 
double linear_x_
 
double linear_y_
 
RollingMeanAcc rear_steer_vel_acc_
 
double rear_steer_vel_prev_
 
double steering_track_
 Wheel kinematic parameters [m]: More...
 
size_t velocity_rolling_window_size_
 Rolling mean accumulators for the linar and angular velocities: More...
 
double wheel_base_
 
double wheel_old_pos_
 Previous wheel position/state [rad]: More...
 
double wheel_radius_
 
double wheel_steering_y_offset_
 
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 52 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 57 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 205 of file odometry.h.

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

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

Member Function Documentation

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

angular velocity getter

Returns
angular velocity [rad/s]

Definition at line 146 of file odometry.h.

double four_wheel_steering_controller::Odometry::getFrontSteerVel ( ) const
inline

front steering velocity getter

Returns
front_steer_vel [m/s³]

Definition at line 173 of file odometry.h.

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

heading getter

Returns
heading [rad]

Definition at line 91 of file odometry.h.

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

linear velocity getter norm

Returns
linear velocity [m/s]

Definition at line 119 of file odometry.h.

double four_wheel_steering_controller::Odometry::getLinearAcceleration ( ) const
inline

linear acceleration getter

Returns
linear acceleration [m/s²]

Definition at line 155 of file odometry.h.

double four_wheel_steering_controller::Odometry::getLinearJerk ( ) const
inline

linear jerk getter

Returns
linear jerk [m/s³]

Definition at line 164 of file odometry.h.

double four_wheel_steering_controller::Odometry::getLinearX ( ) const
inline

linear velocity getter along X on the robot base link frame

Returns
linear velocity [m/s]

Definition at line 128 of file odometry.h.

double four_wheel_steering_controller::Odometry::getLinearY ( ) const
inline

linear velocity getter along Y on the robot base link frame

Returns
linear velocity [m/s]

Definition at line 137 of file odometry.h.

double four_wheel_steering_controller::Odometry::getRearSteerVel ( ) const
inline

rear steering velocity getter

Returns
rear_steer_vel [m/s³]

Definition at line 182 of file odometry.h.

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

x position getter

Returns
x position [m]

Definition at line 100 of file odometry.h.

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

y position getter

Returns
y position [m]

Definition at line 109 of file odometry.h.

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

Initialize the odometry.

Parameters
timeCurrent time

Definition at line 65 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 computed by encoders
angularAngular velocity rad computed by encoders

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

Definition at line 158 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 computed by encoders
angularAngular velocity rad computed by encoders

Runge-Kutta 2nd order integration:

Definition at line 148 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 computed by encoders
linear_yLinear velocity along y of the robot frame m computed by encoders
angularAngular velocity rad computed by encoders

Definition at line 138 of file odometry.cpp.

void four_wheel_steering_controller::Odometry::resetAccumulators ( )
private

Reset linear and angular accumulators.

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

void four_wheel_steering_controller::Odometry::setWheelParams ( double  steering_track,
double  wheel_steering_y_offset,
double  wheel_radius,
double  wheel_base 
)

Sets the wheel parameters: radius and separation.

Parameters
steering_trackSeperation between left and right steering joints [m]
wheel_steering_y_offsetOffest between the steering and wheel joints [m]
wheel_radiusWheel radius [m]
wheel_baseWheel base [m]

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

Member Data Documentation

double four_wheel_steering_controller::Odometry::angular_
private

Definition at line 245 of file odometry.h.

RollingMeanAcc four_wheel_steering_controller::Odometry::front_steer_vel_acc_
private

Definition at line 260 of file odometry.h.

double four_wheel_steering_controller::Odometry::front_steer_vel_prev_
private

Definition at line 263 of file odometry.h.

double four_wheel_steering_controller::Odometry::heading_
private

Definition at line 241 of file odometry.h.

ros::Time four_wheel_steering_controller::Odometry::last_update_timestamp_
private

Current timestamp:

Definition at line 236 of file odometry.h.

double four_wheel_steering_controller::Odometry::linear_
private

Current velocity:

Definition at line 244 of file odometry.h.

RollingMeanAcc four_wheel_steering_controller::Odometry::linear_accel_acc_
private

Definition at line 258 of file odometry.h.

double four_wheel_steering_controller::Odometry::linear_accel_prev_
private

Definition at line 262 of file odometry.h.

RollingMeanAcc four_wheel_steering_controller::Odometry::linear_jerk_acc_
private

Definition at line 259 of file odometry.h.

double four_wheel_steering_controller::Odometry::linear_vel_prev_
private

Definition at line 262 of file odometry.h.

double four_wheel_steering_controller::Odometry::linear_x_
private

Definition at line 244 of file odometry.h.

double four_wheel_steering_controller::Odometry::linear_y_
private

Definition at line 244 of file odometry.h.

RollingMeanAcc four_wheel_steering_controller::Odometry::rear_steer_vel_acc_
private

Definition at line 261 of file odometry.h.

double four_wheel_steering_controller::Odometry::rear_steer_vel_prev_
private

Definition at line 263 of file odometry.h.

double four_wheel_steering_controller::Odometry::steering_track_
private

Wheel kinematic parameters [m]:

Definition at line 248 of file odometry.h.

size_t four_wheel_steering_controller::Odometry::velocity_rolling_window_size_
private

Rolling mean accumulators for the linar and angular velocities:

Definition at line 257 of file odometry.h.

double four_wheel_steering_controller::Odometry::wheel_base_
private

Definition at line 251 of file odometry.h.

double four_wheel_steering_controller::Odometry::wheel_old_pos_
private

Previous wheel position/state [rad]:

Definition at line 254 of file odometry.h.

double four_wheel_steering_controller::Odometry::wheel_radius_
private

Definition at line 250 of file odometry.h.

double four_wheel_steering_controller::Odometry::wheel_steering_y_offset_
private

Definition at line 249 of file odometry.h.

double four_wheel_steering_controller::Odometry::x_
private

Current pose:

Definition at line 239 of file odometry.h.

double four_wheel_steering_controller::Odometry::y_
private

Definition at line 240 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 Thu Apr 11 2019 03:08:25