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: | |
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_ |
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition at line 19 of file odometry.h.
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.
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.
velocity_rolling_window_size | Rolling window size used to compute the velocity mean |
Definition at line 9 of file odometry.cpp.
double four_wheel_steering_controller::Odometry::getAngular | ( | ) | const [inline] |
double four_wheel_steering_controller::Odometry::getHeading | ( | ) | const [inline] |
double four_wheel_steering_controller::Odometry::getLinear | ( | ) | const [inline] |
double four_wheel_steering_controller::Odometry::getLinearX | ( | ) | const [inline] |
linear velocity getter along X on the robot base link frame
Definition at line 103 of file odometry.h.
double four_wheel_steering_controller::Odometry::getLinearY | ( | ) | const [inline] |
linear velocity getter along Y on the robot base link frame
Definition at line 112 of file odometry.h.
double four_wheel_steering_controller::Odometry::getX | ( | ) | const [inline] |
double four_wheel_steering_controller::Odometry::getY | ( | ) | const [inline] |
void four_wheel_steering_controller::Odometry::init | ( | const ros::Time & | time | ) |
void four_wheel_steering_controller::Odometry::integrateExact | ( | double | linear, |
double | angular | ||
) | [private] |
Integrates the velocities (linear and angular) using exact method.
linear | Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by encoders |
angular | Angular 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.
linear | Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by encoders |
angular | Angular 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)
linear_x | Linear velocity along x of the robot frame [m] (linear displacement, i.e. m/s * dt) computed by encoders |
linear_y | Linear velocity along y of the robot frame [m] (linear displacement, i.e. m/s * dt) computed by encoders |
angular | Angular velocity [rad] (angular displacement, i.e. m/s * dt) computed by encoders |
Definition at line 91 of file odometry.cpp.
void four_wheel_steering_controller::Odometry::resetAccumulators | ( | ) | [private] |
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.
velocity_rolling_window_size | Velocity 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.
track | Seperation between left and right wheels [m] |
wheel_radius | Wheel radius [m] |
wheel_base | Wheel 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.
fl_speed | front left wheel vehicle speed [rad/s] |
fr_speed | front right wheel vehicle speed [rad/s] |
rl_speed | rear left wheel vehicle speed [rad/s] |
rr_speed | rear right wheel vehicle speed [rad/s] |
front_steering | steering position [rad] |
rear_steering | steering position [rad] |
time | Current time |
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.
linear | Linear velocity [m/s] |
angular | Angular velocity [rad/s] |
time | Current time |
Save last linear and angular velocity:
Integrate odometry:
Definition at line 65 of file odometry.cpp.
double four_wheel_steering_controller::Odometry::angular_ [private] |
Definition at line 183 of file odometry.h.
Definition at line 196 of file odometry.h.
double four_wheel_steering_controller::Odometry::heading_ [private] |
Definition at line 179 of file odometry.h.
Definition at line 174 of file odometry.h.
double four_wheel_steering_controller::Odometry::linear_ [private] |
Current velocity:
Definition at line 182 of file odometry.h.
Definition at line 195 of file odometry.h.
double four_wheel_steering_controller::Odometry::linear_x_ [private] |
Definition at line 182 of file odometry.h.
double four_wheel_steering_controller::Odometry::linear_y_ [private] |
Definition at line 182 of file odometry.h.
Current timestamp:
Definition at line 174 of file odometry.h.
double four_wheel_steering_controller::Odometry::track_ [private] |
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.
double four_wheel_steering_controller::Odometry::wheel_base_ [private] |
Definition at line 188 of file odometry.h.
double four_wheel_steering_controller::Odometry::wheel_old_pos_ [private] |
Previous wheel position/state [rad]:
Definition at line 191 of file odometry.h.
double four_wheel_steering_controller::Odometry::wheel_radius_ [private] |
Definition at line 187 of file odometry.h.
double four_wheel_steering_controller::Odometry::x_ [private] |
Current pose:
Definition at line 177 of file odometry.h.
double four_wheel_steering_controller::Odometry::y_ [private] |
Definition at line 178 of file odometry.h.