Go to the documentation of this file.
46 #include <boost/bind.hpp>
50 namespace bacc = boost::accumulators;
59 , wheel_separation_(0.0)
60 , left_wheel_radius_(0.0)
61 , right_wheel_radius_(0.0)
62 , left_wheel_old_pos_(0.0)
63 , right_wheel_old_pos_(0.0)
64 , velocity_rolling_window_size_(velocity_rolling_window_size)
65 , linear_acc_(
RollingWindow::window_size = velocity_rolling_window_size)
66 , angular_acc_(
RollingWindow::window_size = velocity_rolling_window_size)
67 , integrate_fun_(
boost::bind(&
Odometry::integrateExact, this, _1, _2))
93 const double linear = (right_wheel_est_vel + left_wheel_est_vel) * 0.5 ;
94 const double angular = (right_wheel_est_vel - left_wheel_est_vel) /
wheel_separation_;
100 const double dt = (time -
timestamp_).toSec();
123 const double dt = (time -
timestamp_).toSec();
144 const double direction =
heading_ + angular * 0.5;
147 x_ += linear * cos(direction);
148 y_ += linear * sin(direction);
159 if (fabs(angular) < 1e-6)
164 const double heading_old =
heading_;
165 const double r = linear/angular;
168 y_ += -r * (cos(
heading_) - cos(heading_old));
bacc::accumulator_set< double, bacc::stats< bacc::tag::rolling_mean > > RollingMeanAcc
Rolling mean accumulator and window:
double right_wheel_radius_
RollingMeanAcc angular_acc_
void integrateExact(double linear, double angular)
Integrates the velocities (linear and angular) using exact method.
size_t velocity_rolling_window_size_
Rolling mean accumulators for the linar and angular velocities:
Odometry(size_t velocity_rolling_window_size=10)
Constructor Timestamp will get the current time value Value will be set to zero.
double right_wheel_old_pos_
double left_wheel_old_pos_
Previou wheel position/state [rad]:
void integrateRungeKutta2(double linear, double angular)
Integrates the velocities (linear and angular) using 2nd order Runge-Kutta.
void init(const ros::Time &time)
Initialize the odometry.
bacc::tag::rolling_window RollingWindow
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
void resetAccumulators()
Reset linear and angular accumulators.
double linear_
Current velocity:
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
bool update(double left_pos, double right_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.
double wheel_separation_
Wheel kinematic parameters [m]:
void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius)
Sets the wheel parameters: radius and separation.
ros::Time timestamp_
Current timestamp:
RollingMeanAcc linear_acc_
double left_wheel_radius_
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
IntegrationFunction integrate_fun_
Integration funcion, used to integrate the odometry: