46 namespace bacc = boost::accumulators;
55 , wheel_separation_(0.0)
56 , left_wheel_radius_(0.0)
57 , right_wheel_radius_(0.0)
58 , left_wheel_old_pos_(0.0)
59 , right_wheel_old_pos_(0.0)
60 , velocity_rolling_window_size_(velocity_rolling_window_size)
61 , linear_acc_(RollingWindow::window_size = velocity_rolling_window_size)
62 , angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
63 , integrate_fun_(
std::bind(&Odometry::integrateExact, this,
std::placeholders::_1,
std::placeholders::_2))
67 void Odometry::init(
const ros::Time& time)
74 bool Odometry::update(
double left_pos,
double right_pos,
const ros::Time &time)
77 const double left_wheel_cur_pos = left_pos * left_wheel_radius_;
78 const double right_wheel_cur_pos = right_pos * right_wheel_radius_;
81 const double left_wheel_est_vel = left_wheel_cur_pos - left_wheel_old_pos_;
82 const double right_wheel_est_vel = right_wheel_cur_pos - right_wheel_old_pos_;
85 left_wheel_old_pos_ = left_wheel_cur_pos;
86 right_wheel_old_pos_ = right_wheel_cur_pos;
89 const double linear = (right_wheel_est_vel + left_wheel_est_vel) * 0.5 ;
90 const double angular = (right_wheel_est_vel - left_wheel_est_vel) / wheel_separation_;
93 integrate_fun_(linear, angular);
96 const double dt = (time - timestamp_).toSec();
103 linear_acc_(linear/dt);
104 angular_acc_(angular/dt);
106 linear_ = bacc::rolling_mean(linear_acc_);
107 angular_ = bacc::rolling_mean(angular_acc_);
112 void Odometry::updateOpenLoop(
double linear,
double angular,
const ros::Time &time)
119 const double dt = (time - timestamp_).toSec();
121 integrate_fun_(linear * dt, angular * dt);
124 void Odometry::setWheelParams(
double wheel_separation,
double left_wheel_radius,
double right_wheel_radius)
126 wheel_separation_ = wheel_separation;
127 left_wheel_radius_ = left_wheel_radius;
128 right_wheel_radius_ = right_wheel_radius;
131 void Odometry::setVelocityRollingWindowSize(
size_t velocity_rolling_window_size)
133 velocity_rolling_window_size_ = velocity_rolling_window_size;
138 void Odometry::integrateRungeKutta2(
double linear,
double angular)
140 const double direction = heading_ + angular * 0.5;
143 x_ += linear * cos(direction);
144 y_ += linear * sin(direction);
153 void Odometry::integrateExact(
double linear,
double angular)
155 if (fabs(angular) < 1e-6)
156 integrateRungeKutta2(linear, angular);
160 const double heading_old = heading_;
161 const double r = linear/angular;
163 x_ += r * (sin(heading_) - sin(heading_old));
164 y_ += -r * (cos(heading_) - cos(heading_old));
168 void Odometry::resetAccumulators()
170 linear_acc_ =
RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
171 angular_acc_ =
RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);