46 #include <boost/bind.hpp> 51 namespace bacc = boost::accumulators;
62 , wheel_separation_(0.0)
63 , velocity_rolling_window_size_(velocity_rolling_window_size)
64 , linear_acc_(
RollingWindow::window_size = velocity_rolling_window_size)
65 , angular_acc_(
RollingWindow::window_size = velocity_rolling_window_size)
66 , integrate_fun_(
boost::bind(&
Odometry::integrateExact, this, _1, _2))
108 const double dt = (time -
timestamp_).toSec();
136 tf::Vector3 vel_inOdom = R_m_odom * tf::Vector3(linear, 0.0, 0.0);
139 x_ += vel_inOdom.x();
140 y_ += vel_inOdom.y();
bacc::accumulator_set< double, bacc::stats< bacc::tag::rolling_mean > > RollingMeanAcc
Rolling mean accumulator and window:
IntegrationFunction integrate_fun_
Integration funcion, used to integrate the odometry:
void integrateExact(double linear, double angular)
Integrates the velocities (linear and angular) using exact method.
void setGearRatios(double drive_motor_gear_ratio, double steer_motor_gear_ratio)
Sets the gear ratio parameters: gear ratio.
double linear_
Current velocity:
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
Odometry(size_t velocity_rolling_window_size=10)
Constructor Timestamp will get the current time value Value will be set to zero.
static Quaternion createQuaternionFromYaw(double yaw)
double drive_motor_gear_ratio_
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
double steer_motor_gear_ratio_
ros::Time timestamp_
Current timestamp:
bacc::tag::rolling_window RollingWindow
RollingMeanAcc linear_acc_
void init(const ros::Time &time)
Initialize the odometry.
void setWheelsParams(double wheel_radius, double wheel_separation)
Sets the wheels parameters: radius and seperation.
bool update(double drive_motor_vel, double steer_motor_vel, const ros::Time &time)
Updates the odometry class with latest wheels position.
size_t velocity_rolling_window_size_
Rolling mean accumulators for the linar and angular velocities:
RollingMeanAcc angular_acc_
double wheel_radius_
Wheels kinematic parameters [m]: