Go to the documentation of this file.
39 #include <boost/accumulators/accumulators.hpp>
40 #include <boost/accumulators/statistics/stats.hpp>
41 #include <boost/accumulators/statistics/rolling_mean.hpp>
42 #include <boost/function.hpp>
46 namespace bacc = boost::accumulators;
65 Odometry(
size_t velocity_rolling_window_size = 10);
84 bool update(
const double& fl_speed,
const double& fr_speed,
const double& rl_speed,
const double& rr_speed,
85 double front_steering,
double rear_steering,
const ros::Time &time);
194 void setWheelParams(
double steering_track,
double wheel_steering_y_offset,
double wheel_radius,
double wheel_base);
205 typedef bacc::accumulator_set<double, bacc::stats<bacc::tag::rolling_mean> >
RollingMeanAcc;
214 void integrateXY(
double linear_x,
double linear_y,
double angular);
double front_steer_vel_prev_
Odometry(size_t velocity_rolling_window_size=10)
Constructor Timestamp will get the current time value Value will be set to zero.
size_t velocity_rolling_window_size_
Rolling mean accumulators for the linar and angular velocities:
void init(const ros::Time &time)
Initialize the odometry.
double getX() const
x position getter
RollingMeanAcc linear_accel_acc_
RollingMeanAcc front_steer_vel_acc_
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
double rear_steer_vel_prev_
double getAngular() const
angular velocity getter
bacc::accumulator_set< double, bacc::stats< bacc::tag::rolling_mean > > RollingMeanAcc
Rolling mean accumulator and window:
void setWheelParams(double steering_track, double wheel_steering_y_offset, double wheel_radius, double wheel_base)
Sets the wheel parameters: radius and separation.
RollingMeanAcc rear_steer_vel_acc_
double getHeading() const
heading getter
boost::function< void(double, double)> IntegrationFunction
Integration function, used to integrate the odometry:
double getLinearAcceleration() const
linear acceleration getter
void resetAccumulators()
Reset linear and angular accumulators.
double linear_
Current velocity:
double getFrontSteerVel() const
front steering velocity getter
double wheel_steering_y_offset_
double getLinear() const
linear velocity getter norm
double getLinearX() const
linear velocity getter along X on the robot base link frame
ros::Time last_update_timestamp_
Current timestamp:
bacc::tag::rolling_window RollingWindow
double getRearSteerVel() const
rear steering velocity getter
bool update(const double &fl_speed, const double &fr_speed, const double &rl_speed, const double &rr_speed, double front_steering, double rear_steering, const ros::Time &time)
Updates the odometry class with latest wheels and steerings position.
double getLinearJerk() const
linear jerk getter
double wheel_old_pos_
Previous wheel position/state [rad]:
double linear_accel_prev_
double getY() const
y position getter
void integrateRungeKutta2(double linear, double angular)
Integrates the velocities (linear and angular) using 2nd order Runge-Kutta.
void integrateXY(double linear_x, double linear_y, double angular)
Integrates the velocities (linear on x and y and angular)
double getLinearY() const
linear velocity getter along Y on the robot base link frame
void integrateExact(double linear, double angular)
Integrates the velocities (linear and angular) using exact method.
RollingMeanAcc linear_jerk_acc_
double steering_track_
Wheel kinematic parameters [m]: