-
Notifications
You must be signed in to change notification settings - Fork 527
/
odometry.cpp
176 lines (150 loc) · 5.97 KB
/
odometry.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2013, PAL Robotics, S.L.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the PAL Robotics nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/*
* Author: Luca Marchionni
* Author: Bence Magyar
* Author: Enrique Fernández
* Author: Paul Mathieu
*/
#include <diff_drive_controller/odometry.h>
#include <boost/bind.hpp>
namespace diff_drive_controller
{
namespace bacc = boost::accumulators;
Odometry::Odometry(size_t velocity_rolling_window_size)
: timestamp_(0.0)
, x_(0.0)
, y_(0.0)
, heading_(0.0)
, linear_(0.0)
, angular_(0.0)
, wheel_separation_(0.0)
, left_wheel_radius_(0.0)
, right_wheel_radius_(0.0)
, left_wheel_old_pos_(0.0)
, right_wheel_old_pos_(0.0)
, velocity_rolling_window_size_(velocity_rolling_window_size)
, linear_acc_(RollingWindow::window_size = velocity_rolling_window_size)
, angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
, integrate_fun_(boost::bind(&Odometry::integrateExact, this, _1, _2))
{
}
void Odometry::init(const ros::Time& time)
{
// Reset accumulators and timestamp:
resetAccumulators();
timestamp_ = time;
}
bool Odometry::update(double left_pos, double right_pos, const ros::Time &time)
{
/// Get current wheel joint positions:
const double left_wheel_cur_pos = left_pos * left_wheel_radius_;
const double right_wheel_cur_pos = right_pos * right_wheel_radius_;
/// Estimate velocity of wheels using old and current position:
const double left_wheel_est_vel = left_wheel_cur_pos - left_wheel_old_pos_;
const double right_wheel_est_vel = right_wheel_cur_pos - right_wheel_old_pos_;
/// Update old position with current:
left_wheel_old_pos_ = left_wheel_cur_pos;
right_wheel_old_pos_ = right_wheel_cur_pos;
/// Compute linear and angular diff:
const double linear = (right_wheel_est_vel + left_wheel_est_vel) * 0.5 ;
const double angular = (right_wheel_est_vel - left_wheel_est_vel) / wheel_separation_;
/// Integrate odometry:
integrate_fun_(linear, angular);
/// We cannot estimate the speed with very small time intervals:
const double dt = (time - timestamp_).toSec();
if (dt < 0.0001)
return false; // Interval too small to integrate with
timestamp_ = time;
/// Estimate speeds using a rolling mean to filter them out:
linear_acc_(linear/dt);
angular_acc_(angular/dt);
linear_ = bacc::rolling_mean(linear_acc_);
angular_ = bacc::rolling_mean(angular_acc_);
return true;
}
void Odometry::updateOpenLoop(double linear, double angular, const ros::Time &time)
{
/// Save last linear and angular velocity:
linear_ = linear;
angular_ = angular;
/// Integrate odometry:
const double dt = (time - timestamp_).toSec();
timestamp_ = time;
integrate_fun_(linear * dt, angular * dt);
}
void Odometry::setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius)
{
wheel_separation_ = wheel_separation;
left_wheel_radius_ = left_wheel_radius;
right_wheel_radius_ = right_wheel_radius;
}
void Odometry::setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
{
velocity_rolling_window_size_ = velocity_rolling_window_size;
resetAccumulators();
}
void Odometry::integrateRungeKutta2(double linear, double angular)
{
const double direction = heading_ + angular * 0.5;
/// Runge-Kutta 2nd order integration:
x_ += linear * cos(direction);
y_ += linear * sin(direction);
heading_ += angular;
}
/**
* \brief Other possible integration method provided by the class
* \param linear
* \param angular
*/
void Odometry::integrateExact(double linear, double angular)
{
if (fabs(angular) < 1e-6)
integrateRungeKutta2(linear, angular);
else
{
/// Exact integration (should solve problems when angular is zero):
const double heading_old = heading_;
const double r = linear/angular;
heading_ += angular;
x_ += r * (sin(heading_) - sin(heading_old));
y_ += -r * (cos(heading_) - cos(heading_old));
}
}
void Odometry::resetAccumulators()
{
linear_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
angular_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
}
} // namespace diff_drive_controller