ros2_control - foxy
Loading...
Searching...
No Matches
ros2_controllers
diff_drive_controller
include
diff_drive_controller
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 "diff_drive_controller/rolling_mean_accumulator.hpp"
28
#include "rclcpp/time.hpp"
29
30
namespace
diff_drive_controller
31
{
32
class
Odometry
33
{
34
public
:
35
explicit
Odometry
(
size_t
velocity_rolling_window_size = 10);
36
37
void
init(
const
rclcpp::Time & time);
38
bool
update(
double
left_pos,
double
right_pos,
const
rclcpp::Time & time);
39
void
updateOpenLoop
(
double
linear,
double
angular,
const
rclcpp::Time & time);
40
void
resetOdometry();
41
42
double
getX()
const
{
return
x_; }
43
double
getY()
const
{
return
y_; }
44
double
getHeading()
const
{
return
heading_; }
45
double
getLinear()
const
{
return
linear_; }
46
double
getAngular()
const
{
return
angular_; }
47
48
void
setWheelParams(
double
wheel_separation,
double
left_wheel_radius,
double
right_wheel_radius);
49
void
setVelocityRollingWindowSize(
size_t
velocity_rolling_window_size);
50
51
private
:
52
using
RollingMeanAccumulator
=
diff_drive_controller::RollingMeanAccumulator<double>
;
53
54
void
integrateRungeKutta2(
double
linear,
double
angular);
55
void
integrateExact(
double
linear,
double
angular);
56
void
resetAccumulators();
57
58
// Current timestamp:
59
rclcpp::Time timestamp_;
60
61
// Current pose:
62
double
x_;
// [m]
63
double
y_;
// [m]
64
double
heading_;
// [rad]
65
66
// Current velocity:
67
double
linear_;
// [m/s]
68
double
angular_;
// [rad/s]
69
70
// Wheel kinematic parameters [m]:
71
double
wheel_separation_;
72
double
left_wheel_radius_;
73
double
right_wheel_radius_;
74
75
// Previous wheel position/state [rad]:
76
double
left_wheel_old_pos_;
77
double
right_wheel_old_pos_;
78
79
// Rolling mean accumulators for the linear and angular velocities:
80
size_t
velocity_rolling_window_size_;
81
RollingMeanAccumulator
linear_accumulator_;
82
RollingMeanAccumulator
angular_accumulator_;
83
};
84
85
}
// namespace diff_drive_controller
86
87
#endif
// DIFF_DRIVE_CONTROLLER__ODOMETRY_HPP_
diff_drive_controller::Odometry
Definition
odometry.hpp:33
diff_drive_controller::Odometry::updateOpenLoop
void updateOpenLoop(double linear, double angular, const rclcpp::Time &time)
Definition
odometry.cpp:89
diff_drive_controller::RollingMeanAccumulator< double >
Generated by
1.9.8