odometry.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, PAL Robotics, S.L.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the PAL Robotics nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /*
36 * Author: Luca Marchionni
37 * Author: Bence Magyar
38 * Author: Enrique Fernández
39 * Author: Paul Mathieu
40 *
41 * Author: Braden McDorman (Semio AI, Inc.)
42 */
43 
45 
46 #include <boost/bind.hpp>
47 
48 using namespace quori_holonomic_drive_controller;
49 
50 namespace bacc = boost::accumulators;
51 
52 Odometry::Odometry(size_t velocity_rolling_window_size)
53 : timestamp_(0.0)
54 , x_(0.0)
55 , y_(0.0)
56 , heading_(0.0)
57 , linear_(0.0)
58 , angular_(0.0)
59 , wheel_separation_(0.0)
60 , left_wheel_radius_(0.0)
61 , right_wheel_radius_(0.0)
62 , left_wheel_old_pos_(0.0)
63 , right_wheel_old_pos_(0.0)
64 , velocity_rolling_window_size_(velocity_rolling_window_size)
65 , linear_acc_(RollingWindow::window_size = velocity_rolling_window_size)
66 , angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
67 , integrate_fun_(boost::bind(&Odometry::integrateExact, this, _1, _2))
68 {
69 }
70 
71 void Odometry::init(const ros::Time& time)
72 {
73  // Reset accumulators and timestamp:
75  timestamp_ = time;
76 }
77 
78 bool Odometry::update(double left_pos, double right_pos, const ros::Time &time)
79 {
81  const double left_wheel_cur_pos = left_pos * left_wheel_radius_;
82  const double right_wheel_cur_pos = right_pos * right_wheel_radius_;
83 
85  const double left_wheel_est_vel = left_wheel_cur_pos - left_wheel_old_pos_;
86  const double right_wheel_est_vel = right_wheel_cur_pos - right_wheel_old_pos_;
87 
89  left_wheel_old_pos_ = left_wheel_cur_pos;
90  right_wheel_old_pos_ = right_wheel_cur_pos;
91 
93  const double linear = (right_wheel_est_vel + left_wheel_est_vel) * 0.5 ;
94  const double angular = (right_wheel_est_vel - left_wheel_est_vel) / wheel_separation_;
95 
97  integrate_fun_(linear, angular);
98 
100  const double dt = (time - timestamp_).toSec();
101  if (dt < 0.0001)
102  return false; // Interval too small to integrate with
103 
104  timestamp_ = time;
105 
107  linear_acc_(linear/dt);
108  angular_acc_(angular/dt);
109 
110  linear_ = bacc::rolling_mean(linear_acc_);
111  angular_ = bacc::rolling_mean(angular_acc_);
112 
113  return true;
114 }
115 
116 void Odometry::updateOpenLoop(double linear, double angular, const ros::Time &time)
117 {
119  linear_ = linear;
120  angular_ = angular;
121 
123  const double dt = (time - timestamp_).toSec();
124  timestamp_ = time;
125  integrate_fun_(linear * dt, angular * dt);
126 }
127 
128 void Odometry::setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius)
129 {
130  wheel_separation_ = wheel_separation;
131  left_wheel_radius_ = left_wheel_radius;
132  right_wheel_radius_ = right_wheel_radius;
133 }
134 
135 void Odometry::setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
136 {
137  velocity_rolling_window_size_ = velocity_rolling_window_size;
138 
140 }
141 
142 void Odometry::integrateRungeKutta2(double linear, double angular)
143 {
144  const double direction = heading_ + angular * 0.5;
145 
147  x_ += linear * cos(direction);
148  y_ += linear * sin(direction);
149  heading_ += angular;
150 }
151 
157 void Odometry::integrateExact(double linear, double angular)
158 {
159  if (fabs(angular) < 1e-6)
160  integrateRungeKutta2(linear, angular);
161  else
162  {
164  const double heading_old = heading_;
165  const double r = linear/angular;
166  heading_ += angular;
167  x_ += r * (sin(heading_) - sin(heading_old));
168  y_ += -r * (cos(heading_) - cos(heading_old));
169  }
170 }
171 
173 {
174  linear_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
175  angular_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
176 }
quori_holonomic_drive_controller::Odometry::RollingMeanAcc
bacc::accumulator_set< double, bacc::stats< bacc::tag::rolling_mean > > RollingMeanAcc
Rolling mean accumulator and window:
Definition: odometry.hpp:225
quori_holonomic_drive_controller::Odometry::right_wheel_radius_
double right_wheel_radius_
Definition: odometry.hpp:262
quori_holonomic_drive_controller::Odometry::angular_acc_
RollingMeanAcc angular_acc_
Definition: odometry.hpp:271
quori_holonomic_drive_controller::Odometry::angular_
double angular_
Definition: odometry.hpp:257
quori_holonomic_drive_controller::Odometry::integrateExact
void integrateExact(double linear, double angular)
Integrates the velocities (linear and angular) using exact method.
Definition: odometry.cpp:157
quori_holonomic_drive_controller::Odometry::velocity_rolling_window_size_
size_t velocity_rolling_window_size_
Rolling mean accumulators for the linar and angular velocities:
Definition: odometry.hpp:269
quori_holonomic_drive_controller::Odometry::Odometry
Odometry(size_t velocity_rolling_window_size=10)
Constructor Timestamp will get the current time value Value will be set to zero.
Definition: odometry.cpp:52
quori_holonomic_drive_controller::Odometry::right_wheel_old_pos_
double right_wheel_old_pos_
Definition: odometry.hpp:266
quori_holonomic_drive_controller::Odometry::left_wheel_old_pos_
double left_wheel_old_pos_
Previou wheel position/state [rad]:
Definition: odometry.hpp:265
boost
quori_holonomic_drive_controller::Odometry::integrateRungeKutta2
void integrateRungeKutta2(double linear, double angular)
Integrates the velocities (linear and angular) using 2nd order Runge-Kutta.
Definition: odometry.cpp:142
quori_holonomic_drive_controller::Odometry::init
void init(const ros::Time &time)
Initialize the odometry.
Definition: odometry.cpp:71
odometry.hpp
quori_holonomic_drive_controller::Odometry::heading_
double heading_
Definition: odometry.hpp:253
quori_holonomic_drive_controller::Odometry::RollingWindow
bacc::tag::rolling_window RollingWindow
Definition: odometry.hpp:226
quori_holonomic_drive_controller
Definition: holonomic.hpp:5
quori_holonomic_drive_controller::Odometry::updateOpenLoop
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
Definition: odometry.cpp:116
quori_holonomic_drive_controller::Odometry::resetAccumulators
void resetAccumulators()
Reset linear and angular accumulators.
Definition: odometry.cpp:172
quori_holonomic_drive_controller::Odometry::linear_
double linear_
Current velocity:
Definition: odometry.hpp:256
quori_holonomic_drive_controller::Odometry
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition: odometry.hpp:93
quori_holonomic_drive_controller::Odometry::update
bool update(double left_pos, double right_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.
Definition: odometry.cpp:78
quori_holonomic_drive_controller::Odometry::wheel_separation_
double wheel_separation_
Wheel kinematic parameters [m]:
Definition: odometry.hpp:260
quori_holonomic_drive_controller::Odometry::setWheelParams
void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius)
Sets the wheel parameters: radius and separation.
Definition: odometry.cpp:128
ros::Time
quori_holonomic_drive_controller::Odometry::timestamp_
ros::Time timestamp_
Current timestamp:
Definition: odometry.hpp:248
quori_holonomic_drive_controller::Odometry::x_
double x_
Current pose:
Definition: odometry.hpp:251
quori_holonomic_drive_controller::Odometry::y_
double y_
Definition: odometry.hpp:252
quori_holonomic_drive_controller::Odometry::linear_acc_
RollingMeanAcc linear_acc_
Definition: odometry.hpp:270
quori_holonomic_drive_controller::Odometry::left_wheel_radius_
double left_wheel_radius_
Definition: odometry.hpp:261
quori_holonomic_drive_controller::Odometry::setVelocityRollingWindowSize
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
Definition: odometry.cpp:135
quori_holonomic_drive_controller::Odometry::integrate_fun_
IntegrationFunction integrate_fun_
Integration funcion, used to integrate the odometry:
Definition: odometry.hpp:274


quori_holonomic_drive_controller
Author(s):
autogenerated on Wed Mar 2 2022 00:53:24