ros2_control - rolling
Loading...
Searching...
No Matches
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
33namespace diff_drive_controller
34{
36{
37public:
38 explicit Odometry(size_t velocity_rolling_window_size = 10);
39
40 [[deprecated]]
41 void init(const rclcpp::Time & time);
42 [[deprecated(
43 "Replaced by bool update_from_pos(double left_pos, double right_pos, double "
44 "dt).")]]
45 bool update(double left_pos, double right_pos, const rclcpp::Time & time);
46 [[deprecated(
47 "Replaced by bool update_from_vel(double left_vel, double right_vel, double "
48 "dt).")]]
49 bool updateFromVelocity(double left_vel, double right_vel, const rclcpp::Time & time);
50 [[deprecated(
51 "Replaced by bool try_update_open_loop(double linear_vel, double angular_vel, double "
52 "dt).")]]
53 void updateOpenLoop(double linear, double angular, const rclcpp::Time & time);
54
55 bool update_from_pos(double left_pos, double right_pos, double dt);
56 bool update_from_vel(double left_vel, double right_vel, double dt);
57 bool try_update_open_loop(double linear_vel, double angular_vel, double dt);
58 void resetOdometry();
59
60 double getX() const { return x_; }
61 double getY() const { return y_; }
62 double getHeading() const { return heading_; }
63 double getLinear() const { return linear_; }
64 double getAngular() const { return angular_; }
65
66 void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius);
67 void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
68
69private:
70// \note The versions conditioning is added here to support the source-compatibility with Humble
71#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
72 using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
73#else
74 using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
75#endif
76
77 [[deprecated("Replaced by void integrate(double linear_vel, double angular_vel, double dt).")]]
78 void integrateRungeKutta2(double linear, double angular);
79 [[deprecated("Replaced by void integrate(double linear_vel, double angular_vel, double dt).")]]
80 void integrateExact(double linear, double angular);
81
82 void integrate(double linear_vel, double angular_vel, double dt);
83 void resetAccumulators();
84
85 // Current timestamp:
86 rclcpp::Time timestamp_;
87
88 // Current pose:
89 double x_; // [m]
90 double y_; // [m]
91 double heading_; // [rad]
92
93 // Current velocity:
94 double linear_; // [m/s]
95 double angular_; // [rad/s]
96
97 // Wheel kinematic parameters [m]:
98 double wheel_separation_;
99 double left_wheel_radius_;
100 double right_wheel_radius_;
101
102 // Previous wheel position/state [rad]:
103 double left_wheel_old_pos_;
104 double right_wheel_old_pos_;
105
106 // Rolling mean accumulators for the linear and angular velocities:
107 size_t velocity_rolling_window_size_;
108 RollingMeanAccumulator linear_accumulator_;
109 RollingMeanAccumulator angular_accumulator_;
110};
111
112} // namespace diff_drive_controller
113
114#endif // DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
Definition odometry.hpp:36
void updateOpenLoop(double linear, double angular, const rclcpp::Time &time)
Definition odometry.cpp:146