47 namespace bacc = boost::accumulators;
56 , wheel_separation_h_(0.0)
58 , rear_wheel_old_pos_(0.0)
59 , velocity_rolling_window_size_(velocity_rolling_window_size)
60 , linear_acc_(RollingWindow::window_size = velocity_rolling_window_size)
61 , angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
62 , integrate_fun_(
std::bind(&Odometry::integrateExact, this,
std::placeholders::_1,
std::placeholders::_2))
66 void Odometry::init(
const ros::Time& time)
73 bool Odometry::update(
double rear_wheel_pos,
double front_steer_pos,
const ros::Time &time)
76 const double rear_wheel_cur_pos = rear_wheel_pos * wheel_radius_;
82 const double rear_wheel_est_vel = rear_wheel_cur_pos - rear_wheel_old_pos_;
85 rear_wheel_old_pos_ = rear_wheel_cur_pos;
88 const double linear = rear_wheel_est_vel;
90 const double angular = tan(front_steer_pos) * linear / wheel_separation_h_;
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_h,
double wheel_radius)
126 wheel_separation_h_ = wheel_separation_h;
127 wheel_radius_ = wheel_radius;
130 void Odometry::setVelocityRollingWindowSize(
size_t velocity_rolling_window_size)
132 velocity_rolling_window_size_ = velocity_rolling_window_size;
137 void Odometry::integrateRungeKutta2(
double linear,
double angular)
139 const double direction = heading_ + angular * 0.5;
142 x_ += linear * cos(direction);
143 y_ += linear * sin(direction);
152 void Odometry::integrateExact(
double linear,
double angular)
154 if (fabs(angular) < 1e-6)
155 integrateRungeKutta2(linear, angular);
159 const double heading_old = heading_;
160 const double r = linear/angular;
162 x_ += r * (sin(heading_) - sin(heading_old));
163 y_ += -r * (cos(heading_) - cos(heading_old));
167 void Odometry::resetAccumulators()
169 linear_acc_ =
RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
170 angular_acc_ =
RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);