22 #ifndef DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
23 #define DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
25 #include "rclcpp/time.hpp"
27 #if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
28 #include "rcpputils/rolling_mean_accumulator.hpp"
30 #include "rcppmath/rolling_mean_accumulator.hpp"
33 namespace diff_drive_controller
38 explicit Odometry(
size_t velocity_rolling_window_size = 10);
40 void init(
const rclcpp::Time & time);
41 bool update(
double left_pos,
double right_pos,
const rclcpp::Time & time);
42 bool updateFromVelocity(
double left_vel,
double right_vel,
const rclcpp::Time & time);
43 void updateOpenLoop(
double linear,
double angular,
const rclcpp::Time & time);
46 double getX()
const {
return x_; }
47 double getY()
const {
return y_; }
48 double getHeading()
const {
return heading_; }
49 double getLinear()
const {
return linear_; }
50 double getAngular()
const {
return angular_; }
52 void setWheelParams(
double wheel_separation,
double left_wheel_radius,
double right_wheel_radius);
53 void setVelocityRollingWindowSize(
size_t velocity_rolling_window_size);
57 #if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
58 using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
60 using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
63 void integrateRungeKutta2(
double linear,
double angular);
64 void integrateExact(
double linear,
double angular);
65 void resetAccumulators();
68 rclcpp::Time timestamp_;
80 double wheel_separation_;
81 double left_wheel_radius_;
82 double right_wheel_radius_;
85 double left_wheel_old_pos_;
86 double right_wheel_old_pos_;
89 size_t velocity_rolling_window_size_;
90 RollingMeanAccumulator linear_accumulator_;
91 RollingMeanAccumulator angular_accumulator_;
Definition: odometry.hpp:36
void updateOpenLoop(double linear, double angular, const rclcpp::Time &time)
Definition: odometry.cpp:100