ros2_control - rolling
odometry.hpp
1 // Copyright 2020 PAL Robotics S.L.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 /*
16  * Author: Luca Marchionni
17  * Author: Bence Magyar
18  * Author: Enrique Fernández
19  * Author: Paul Mathieu
20  */
21 
22 #ifndef DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
23 #define DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
24 
25 #include <cmath>
26 
27 #include "rclcpp/time.hpp"
28 // \note The versions conditioning is added here to support the source-compatibility with Humble
29 #if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
30 #include "rcpputils/rolling_mean_accumulator.hpp"
31 #else
32 #include "rcppmath/rolling_mean_accumulator.hpp"
33 #endif
34 
35 namespace diff_drive_controller
36 {
37 class Odometry
38 {
39 public:
40  explicit Odometry(size_t velocity_rolling_window_size = 10);
41 
42  void init(const rclcpp::Time & time);
43  bool update(double left_pos, double right_pos, const rclcpp::Time & time);
44  bool updateFromVelocity(double left_vel, double right_vel, const rclcpp::Time & time);
45  void updateOpenLoop(double linear, double angular, const rclcpp::Time & time);
46  void resetOdometry();
47 
48  double getX() const { return x_; }
49  double getY() const { return y_; }
50  double getHeading() const { return heading_; }
51  double getLinear() const { return linear_; }
52  double getAngular() const { return angular_; }
53 
54  void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius);
55  void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
56 
57 private:
58 // \note The versions conditioning is added here to support the source-compatibility with Humble
59 #if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
60  using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
61 #else
62  using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
63 #endif
64 
65  void integrateRungeKutta2(double linear, double angular);
66  void integrateExact(double linear, double angular);
67  void resetAccumulators();
68 
69  // Current timestamp:
70  rclcpp::Time timestamp_;
71 
72  // Current pose:
73  double x_; // [m]
74  double y_; // [m]
75  double heading_; // [rad]
76 
77  // Current velocity:
78  double linear_; // [m/s]
79  double angular_; // [rad/s]
80 
81  // Wheel kinematic parameters [m]:
82  double wheel_separation_;
83  double left_wheel_radius_;
84  double right_wheel_radius_;
85 
86  // Previous wheel position/state [rad]:
87  double left_wheel_old_pos_;
88  double right_wheel_old_pos_;
89 
90  // Rolling mean accumulators for the linear and angular velocities:
91  size_t velocity_rolling_window_size_;
92  RollingMeanAccumulator linear_accumulator_;
93  RollingMeanAccumulator angular_accumulator_;
94 };
95 
96 } // namespace diff_drive_controller
97 
98 #endif // DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
Definition: odometry.hpp:38
void updateOpenLoop(double linear, double angular, const rclcpp::Time &time)
Definition: odometry.cpp:98