Go to the documentation of this file.
46 #include <boost/accumulators/accumulators.hpp>
47 #include <boost/accumulators/statistics/stats.hpp>
48 #include <boost/accumulators/statistics/rolling_mean.hpp>
49 #include <boost/function.hpp>
53 namespace bacc = boost::accumulators;
72 Odometry(
size_t velocity_rolling_window_size = 10);
148 void setWheelParams(
double wheel_separation,
double left_wheel_radius,
double right_wheel_radius);
159 typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> >
RollingMeanAcc;
void init(const ros::Time &time)
Initialize the odometry.
double getLinear() const
linear velocity getter
void integrateRungeKutta2(double linear, double angular)
Integrates the velocities (linear and angular) using 2nd order Runge-Kutta.
RollingMeanAcc angular_acc_
IntegrationFunction integrate_fun_
Integration funcion, used to integrate the odometry:
double right_wheel_old_pos_
double getX() const
x position getter
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
bacc::tag::rolling_window RollingWindow
bool update(double left_pos, double right_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.
RollingMeanAcc linear_acc_
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.
size_t velocity_rolling_window_size_
Rolling mean accumulators for the linar and angular velocities:
double getHeading() const
heading getter
bacc::accumulator_set< double, bacc::stats< bacc::tag::rolling_mean > > RollingMeanAcc
Rolling mean accumulator and window:
Odometry(size_t velocity_rolling_window_size=10)
Constructor Timestamp will get the current time value Value will be set to zero.
double left_wheel_radius_
void integrateExact(double linear, double angular)
Integrates the velocities (linear and angular) using exact method.
double left_wheel_old_pos_
Previou wheel position/state [rad]:
double right_wheel_radius_
ros::Time timestamp_
Current timestamp:
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.
double getY() const
y position getter
double getAngular() const
angular velocity getter
boost::function< void(double, double)> IntegrationFunction
Integration function, used to integrate the odometry:
double linear_
Current velocity: