44 #include <boost/bind.hpp> 48 namespace bacc = boost::accumulators;
57 , wheel_separation_(0.0)
58 , left_wheel_radius_(0.0)
59 , right_wheel_radius_(0.0)
60 , left_wheel_old_pos_(0.0)
61 , right_wheel_old_pos_(0.0)
62 , velocity_rolling_window_size_(velocity_rolling_window_size)
63 , linear_acc_(
RollingWindow::window_size = velocity_rolling_window_size)
64 , angular_acc_(
RollingWindow::window_size = velocity_rolling_window_size)
65 , integrate_fun_(
boost::bind(&
Odometry::integrateExact, this, _1, _2))
87 left_wheel_old_pos_ = left_wheel_cur_pos;
88 right_wheel_old_pos_ = right_wheel_cur_pos;
91 const double linear = (right_wheel_est_vel + left_wheel_est_vel) * 0.5 ;
92 const double angular = (right_wheel_est_vel - left_wheel_est_vel) /
wheel_separation_;
121 const double dt = (time -
timestamp_).toSec();
142 const double direction =
heading_ + angular * 0.5;
145 x_ += linear * cos(direction);
146 y_ += linear * sin(direction);
157 if (fabs(angular) < 1e-6)
162 const double heading_old =
heading_;
163 const double r = linear/angular;
166 y_ += -r * (cos(
heading_) - cos(heading_old));
bacc::accumulator_set< double, bacc::stats< bacc::tag::rolling_mean > > RollingMeanAcc
Rolling mean accumulator and window:
RollingMeanAcc linear_acc_
bool update(double left_pos, double right_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.
double left_wheel_old_pos_
Previou wheel position/state [rad]:
ros::Time timestamp_
Current timestamp:
double linear_
Current velocity:
Odometry(size_t velocity_rolling_window_size=10)
Constructor Timestamp will get the current time value Value will be set to zero.
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 init(const ros::Time &time)
Initialize the odometry.
RollingMeanAcc angular_acc_
void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius)
Sets the wheel parameters: radius and separation.
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
double right_wheel_old_pos_
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
bacc::tag::rolling_window RollingWindow
size_t velocity_rolling_window_size_
Rolling mean accumulators for the linar and angular velocities:
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
double right_wheel_radius_
double wheel_separation_
Wheel kinematic parameters [m]:
IntegrationFunction integrate_fun_
Integration funcion, used to integrate the odometry:
void resetAccumulators()
Reset linear and angular accumulators.
double left_wheel_radius_