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 "rclcpp/time.hpp"
26 // \note The versions conditioning is added here to support the source-compatibility with Humble
27 #if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
28 #include "rcpputils/rolling_mean_accumulator.hpp"
29 #else
30 #include "rcppmath/rolling_mean_accumulator.hpp"
31 #endif
32 
33 namespace diff_drive_controller
34 {
35 class Odometry
36 {
37 public:
38  explicit Odometry(size_t velocity_rolling_window_size = 10);
39 
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);
44  void resetOdometry();
45 
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_; }
51 
52  void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius);
53  void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
54 
55 private:
56 // \note The versions conditioning is added here to support the source-compatibility with Humble
57 #if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
58  using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
59 #else
60  using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
61 #endif
62 
63  void integrateRungeKutta2(double linear, double angular);
64  void integrateExact(double linear, double angular);
65  void resetAccumulators();
66 
67  // Current timestamp:
68  rclcpp::Time timestamp_;
69 
70  // Current pose:
71  double x_; // [m]
72  double y_; // [m]
73  double heading_; // [rad]
74 
75  // Current velocity:
76  double linear_; // [m/s]
77  double angular_; // [rad/s]
78 
79  // Wheel kinematic parameters [m]:
80  double wheel_separation_;
81  double left_wheel_radius_;
82  double right_wheel_radius_;
83 
84  // Previous wheel position/state [rad]:
85  double left_wheel_old_pos_;
86  double right_wheel_old_pos_;
87 
88  // Rolling mean accumulators for the linear and angular velocities:
89  size_t velocity_rolling_window_size_;
90  RollingMeanAccumulator linear_accumulator_;
91  RollingMeanAccumulator angular_accumulator_;
92 };
93 
94 } // namespace diff_drive_controller
95 
96 #endif // DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
Definition: odometry.hpp:36
void updateOpenLoop(double linear, double angular, const rclcpp::Time &time)
Definition: odometry.cpp:100