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 | |
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 wheel_reparation_h, double wheel_radius) |
Sets the wheel parameters: radius and separation. | |
bool | update (double rear_wheel_pos, double front_steer_pos, const ros::Time &time) |
Updates the odometry class with latest wheels 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 | heading_ |
IntegrationFunction | integrate_fun_ |
Integration funcion, used to integrate the odometry: | |
double | linear_ |
Current velocity: | |
RollingMeanAcc | linear_acc_ |
double | rear_wheel_old_pos_ |
Previous wheel position/state [rad]: | |
ros::Time | timestamp_ |
Current timestamp: | |
size_t | velocity_rolling_window_size_ |
Rolling mean accumulators for the linar and angular velocities: | |
double | wheel_radius_ |
double | wheel_separation_h_ |
Wheel kinematic parameters [m]: | |
double | x_ |
Current pose: | |
double | y_ |
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition at line 59 of file odometry.h.
typedef boost::function<void(double, double)> steer_drive_controller::Odometry::IntegrationFunction |
Integration function, used to integrate the odometry:
Definition at line 64 of file odometry.h.
typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> > steer_drive_controller::Odometry::RollingMeanAcc [private] |
Rolling mean accumulator and window:
Definition at line 158 of file odometry.h.
typedef bacc::tag::rolling_window steer_drive_controller::Odometry::RollingWindow [private] |
Definition at line 159 of file odometry.h.
steer_drive_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 51 of file odometry.cpp.
double steer_drive_controller::Odometry::getAngular | ( | ) | const [inline] |
double steer_drive_controller::Odometry::getHeading | ( | ) | const [inline] |
double steer_drive_controller::Odometry::getLinear | ( | ) | const [inline] |
double steer_drive_controller::Odometry::getX | ( | ) | const [inline] |
double steer_drive_controller::Odometry::getY | ( | ) | const [inline] |
void steer_drive_controller::Odometry::init | ( | const ros::Time & | time | ) |
void steer_drive_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.
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 |
linear | |
angular |
Exact integration (should solve problems when angular is zero):
Definition at line 150 of file odometry.cpp.
void steer_drive_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 135 of file odometry.cpp.
void steer_drive_controller::Odometry::resetAccumulators | ( | ) | [private] |
Reset linear and angular accumulators.
Definition at line 165 of file odometry.cpp.
void steer_drive_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 128 of file odometry.cpp.
void steer_drive_controller::Odometry::setWheelParams | ( | double | wheel_reparation_h, |
double | wheel_radius | ||
) |
Sets the wheel parameters: radius and separation.
wheel_separation | Seperation between left and right wheels [m] |
wheel_radius | Wheel radius [m] |
Definition at line 122 of file odometry.cpp.
bool steer_drive_controller::Odometry::update | ( | double | rear_wheel_pos, |
double | front_steer_pos, | ||
const ros::Time & | time | ||
) |
Updates the odometry class with latest wheels position.
rear_wheel_pos | Rear wheel position [rad] |
front_steer_pos | Front Steer position [rad] |
time | Current time |
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 steer_drive_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 110 of file odometry.cpp.
double steer_drive_controller::Odometry::angular_ [private] |
Definition at line 190 of file odometry.h.
Definition at line 202 of file odometry.h.
double steer_drive_controller::Odometry::heading_ [private] |
Definition at line 186 of file odometry.h.
Integration funcion, used to integrate the odometry:
Definition at line 205 of file odometry.h.
double steer_drive_controller::Odometry::linear_ [private] |
Current velocity:
Definition at line 189 of file odometry.h.
Definition at line 201 of file odometry.h.
double steer_drive_controller::Odometry::rear_wheel_old_pos_ [private] |
Previous wheel position/state [rad]:
Definition at line 197 of file odometry.h.
Current timestamp:
Definition at line 181 of file odometry.h.
size_t steer_drive_controller::Odometry::velocity_rolling_window_size_ [private] |
Rolling mean accumulators for the linar and angular velocities:
Definition at line 200 of file odometry.h.
double steer_drive_controller::Odometry::wheel_radius_ [private] |
Definition at line 194 of file odometry.h.
double steer_drive_controller::Odometry::wheel_separation_h_ [private] |
Wheel kinematic parameters [m]:
Definition at line 193 of file odometry.h.
double steer_drive_controller::Odometry::x_ [private] |
Current pose:
Definition at line 184 of file odometry.h.
double steer_drive_controller::Odometry::y_ [private] |
Definition at line 185 of file odometry.h.