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 | getAngularEstimated () const |
| Retrieves the angular velocity estimation. | |
| double | getHeading () const |
| heading getter | |
| double | getLinearEstimated () const |
| Retrieves the linear velocity estimation. | |
| ros::Time | getTimestamp () const |
| timestamp getter | |
| double | getX () const |
| x position getter | |
| double | getY () const |
| y position getter | |
| Odometry (size_t velocity_rolling_window_size=10) | |
| Constructor Timestamp will get the current time value Value will be set to zero. | |
| void | setWheelParams (double wheel_separation, double wheel_radius) |
| Sets the wheel parameters: radius and separation. | |
| bool | update (double left_pos, double right_pos, const ros::Time &time) |
| Updates the odometry class with latest wheels position. | |
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. | |
Private Attributes | |
| RollingMeanAcc | angular_acc_ |
| double | heading_ |
| IntegrationFunction | integrate_fun_ |
| Integration funcion, used to integrate the odometry: | |
| double | left_wheel_old_pos_ |
| Previou wheel position/state [rad]: | |
| RollingMeanAcc | linear_acc_ |
| Rolling meand accumulators for the linar and angular velocities: | |
| double | right_wheel_old_pos_ |
| ros::Time | timestamp_ |
| Current timestamp: | |
| double | wheel_radius_ |
| double | wheel_separation_ |
| 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 57 of file odometry.h.
| typedef boost::function<void(double, double)> diff_drive_controller::Odometry::IntegrationFunction |
Integration function, used to integrate the odometry:
Definition at line 62 of file odometry.h.
typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> > diff_drive_controller::Odometry::RollingMeanAcc [private] |
Rolling mean accumulator and window:
Definition at line 139 of file odometry.h.
typedef bacc::tag::rolling_window diff_drive_controller::Odometry::RollingWindow [private] |
Definition at line 140 of file odometry.h.
| diff_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 48 of file odometry.cpp.
| double diff_drive_controller::Odometry::getAngularEstimated | ( | ) | const |
Retrieves the angular velocity estimation.
Definition at line 103 of file odometry.cpp.
| double diff_drive_controller::Odometry::getHeading | ( | ) | const [inline] |
| double diff_drive_controller::Odometry::getLinearEstimated | ( | ) | const |
Retrieves the linear velocity estimation.
Definition at line 98 of file odometry.cpp.
| ros::Time diff_drive_controller::Odometry::getTimestamp | ( | ) | const [inline] |
| double diff_drive_controller::Odometry::getX | ( | ) | const [inline] |
| double diff_drive_controller::Odometry::getY | ( | ) | const [inline] |
| void diff_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 132 of file odometry.cpp.
| void diff_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:
Normalization of angle to [-Pi, Pi]:
Definition at line 114 of file odometry.cpp.
| void diff_drive_controller::Odometry::setWheelParams | ( | double | wheel_separation, |
| 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 108 of file odometry.cpp.
| bool diff_drive_controller::Odometry::update | ( | double | left_pos, |
| double | right_pos, | ||
| const ros::Time & | time | ||
| ) |
Updates the odometry class with latest wheels position.
| left_pos | Left wheel position [rad] |
| right_pos | Right wheel 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 63 of file odometry.cpp.
Definition at line 174 of file odometry.h.
double diff_drive_controller::Odometry::heading_ [private] |
Definition at line 162 of file odometry.h.
Integration funcion, used to integrate the odometry:
Definition at line 177 of file odometry.h.
double diff_drive_controller::Odometry::left_wheel_old_pos_ [private] |
Previou wheel position/state [rad]:
Definition at line 169 of file odometry.h.
Rolling meand accumulators for the linar and angular velocities:
Definition at line 173 of file odometry.h.
double diff_drive_controller::Odometry::right_wheel_old_pos_ [private] |
Definition at line 170 of file odometry.h.
Current timestamp:
Definition at line 157 of file odometry.h.
double diff_drive_controller::Odometry::wheel_radius_ [private] |
Definition at line 166 of file odometry.h.
double diff_drive_controller::Odometry::wheel_separation_ [private] |
Wheel kinematic parameters [m]:
Definition at line 165 of file odometry.h.
double diff_drive_controller::Odometry::x_ [private] |
Current pose:
Definition at line 160 of file odometry.h.
double diff_drive_controller::Odometry::y_ [private] |
Definition at line 161 of file odometry.h.