odometry.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Irstea
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 Irstea 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 
36 
38 {
39  namespace bacc = boost::accumulators;
40 
41  Odometry::Odometry(size_t velocity_rolling_window_size)
42  : last_update_timestamp_(0.0)
43  , x_(0.0)
44  , y_(0.0)
45  , heading_(0.0)
46  , linear_(0.0)
47  , linear_x_(0.0)
48  , linear_y_(0.0)
49  , angular_(0.0)
50  , steering_track_(0.0)
51  , wheel_steering_y_offset_(0.0)
52  , wheel_radius_(0.0)
53  , wheel_base_(0.0)
54  , wheel_old_pos_(0.0)
55  , velocity_rolling_window_size_(velocity_rolling_window_size)
56  , linear_accel_acc_(RollingWindow::window_size = velocity_rolling_window_size)
57  , linear_jerk_acc_(RollingWindow::window_size = velocity_rolling_window_size)
58  , front_steer_vel_acc_(RollingWindow::window_size = velocity_rolling_window_size)
59  , rear_steer_vel_acc_(RollingWindow::window_size = velocity_rolling_window_size)
60  {
61  }
62 
63  void Odometry::init(const ros::Time& time)
64  {
65  // Reset accumulators and timestamp:
66  resetAccumulators();
67  last_update_timestamp_ = time;
68  }
69 
70  bool Odometry::update(const double &fl_speed, const double &fr_speed,
71  const double &rl_speed, const double &rr_speed,
72  double front_steering, double rear_steering, const ros::Time &time)
73  {
74  const double front_tmp = cos(front_steering)*(tan(front_steering)-tan(rear_steering))/wheel_base_;
75  const double front_left_tmp = front_tmp/sqrt(1-steering_track_*front_tmp*cos(front_steering)
76  +pow(steering_track_*front_tmp/2,2));
77  const double front_right_tmp = front_tmp/sqrt(1+steering_track_*front_tmp*cos(front_steering)
78  +pow(steering_track_*front_tmp/2,2));
79  const double fl_speed_tmp = fl_speed * (1/(1-wheel_steering_y_offset_*front_left_tmp));
80  const double fr_speed_tmp = fr_speed * (1/(1-wheel_steering_y_offset_*front_right_tmp));
81  const double front_linear_speed = wheel_radius_ * copysign(1.0, fl_speed_tmp+fr_speed_tmp)*
82  sqrt((pow(fl_speed,2)+pow(fr_speed,2))/(2+pow(steering_track_*front_tmp,2)/2.0));
83 
84  const double rear_tmp = cos(rear_steering)*(tan(front_steering)-tan(rear_steering))/wheel_base_;
85  const double rear_left_tmp = rear_tmp/sqrt(1-steering_track_*rear_tmp*cos(rear_steering)
86  +pow(steering_track_*rear_tmp/2,2));
87  const double rear_right_tmp = rear_tmp/sqrt(1+steering_track_*rear_tmp*cos(rear_steering)
88  +pow(steering_track_*rear_tmp/2,2));
89  const double rl_speed_tmp = rl_speed * (1/(1-wheel_steering_y_offset_*rear_left_tmp));
90  const double rr_speed_tmp = rr_speed * (1/(1-wheel_steering_y_offset_*rear_right_tmp));
91  const double rear_linear_speed = wheel_radius_ * copysign(1.0, rl_speed_tmp+rr_speed_tmp)*
92  sqrt((pow(rl_speed_tmp,2)+pow(rr_speed_tmp,2))/(2+pow(steering_track_*rear_tmp,2)/2.0));
93 
94  angular_ = (front_linear_speed*front_tmp + rear_linear_speed*rear_tmp)/2.0;
95 
96  linear_x_ = (front_linear_speed*cos(front_steering) + rear_linear_speed*cos(rear_steering))/2.0;
97  linear_y_ = (front_linear_speed*sin(front_steering) - wheel_base_*angular_/2.0
98  + rear_linear_speed*sin(rear_steering) + wheel_base_*angular_/2.0)/2.0;
99  linear_ = copysign(1.0, rear_linear_speed)*sqrt(pow(linear_x_,2)+pow(linear_y_,2));
100 
102  const double dt = (time - last_update_timestamp_).toSec();
103  if (dt < 0.0001)
104  return false; // Interval too small to integrate with
105 
106  last_update_timestamp_ = time;
108  integrateXY(linear_x_*dt, linear_y_*dt, angular_*dt);
109 
110  linear_accel_acc_((linear_vel_prev_ - linear_)/dt);
111  linear_vel_prev_ = linear_;
112  linear_jerk_acc_((linear_accel_prev_ - bacc::rolling_mean(linear_accel_acc_))/dt);
113  linear_accel_prev_ = bacc::rolling_mean(linear_accel_acc_);
114  front_steer_vel_acc_((front_steer_vel_prev_ - front_steering)/dt);
115  front_steer_vel_prev_ = front_steering;
116  rear_steer_vel_acc_((rear_steer_vel_prev_ - rear_steering)/dt);
117  rear_steer_vel_prev_ = rear_steering;
118  return true;
119  }
120 
121  void Odometry::setWheelParams(double steering_track, double wheel_steering_y_offset, double wheel_radius, double wheel_base)
122  {
123  steering_track_ = steering_track;
124  wheel_steering_y_offset_ = wheel_steering_y_offset;
125  wheel_radius_ = wheel_radius;
126  wheel_base_ = wheel_base;
127  }
128 
129  void Odometry::setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
130  {
131  velocity_rolling_window_size_ = velocity_rolling_window_size;
132 
133  resetAccumulators();
134  }
135 
136  void Odometry::integrateXY(double linear_x, double linear_y, double angular)
137  {
138  const double delta_x = linear_x*cos(heading_) - linear_y*sin(heading_);
139  const double delta_y = linear_x*sin(heading_) + linear_y*cos(heading_);
140 
141  x_ += delta_x;
142  y_ += delta_y;
143  heading_ += angular;
144  }
145 
146  void Odometry::integrateRungeKutta2(double linear, double angular)
147  {
148  const double direction = heading_ + angular * 0.5;
149 
151  x_ += linear * cos(direction);
152  y_ += linear * sin(direction);
153  heading_ += angular;
154  }
155 
156  void Odometry::integrateExact(double linear, double angular)
157  {
158  if (fabs(angular) < 1e-6)
159  integrateRungeKutta2(linear, angular);
160  else
161  {
163  const double heading_old = heading_;
164  const double r = linear/angular;
165  heading_ += angular;
166  x_ += r * (sin(heading_) - sin(heading_old));
167  y_ += -r * (cos(heading_) - cos(heading_old));
168  }
169  }
170 
171  void Odometry::resetAccumulators()
172  {
173  linear_accel_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
174  linear_jerk_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
175  front_steer_vel_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
176  rear_steer_vel_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
177  }
178 
179 } // namespace four_wheel_steering_controller
four_wheel_steering_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:73
odometry.h
four_wheel_steering_controller
Definition: four_wheel_steering_controller.h:52
ros::Time


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri May 24 2024 02:41:15