graceful_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2021-2022 Michael Ferguson
3  * Copyright 2015 Fetch Robotics Inc
4  * Author: Michael Ferguson
5  *
6  * This program is free software: you can redistribute it and/or modify
7  * it under the terms of the GNU Lesser General Public License as published by
8  * the Free Software Foundation, either version 3 of the License, or
9  * (at your option) any later version.
10  *
11  * This program is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU Lesser General Public License for more details.
15  *
16  * You should have received a copy of the GNU Lesser General Public License
17  * along with this program. If not, see <http://www.gnu.org/licenses/>.
18  */
19 
21 
22 #include <angles/angles.h>
23 
24 #include <algorithm>
25 #include <list>
26 #include <vector>
27 #include <cmath>
28 
29 namespace graceful_controller
30 {
31 
33  double min_abs_velocity, double max_abs_velocity,
34  double max_decel,
35  double max_abs_angular_velocity,
36  double beta, double lambda)
37 {
38  k1_ = k1;
39  k2_ = k2;
40  min_abs_velocity_ = min_abs_velocity;
41  max_abs_velocity_ = max_abs_velocity;
42  max_decel_ = max_decel;
43  max_abs_angular_velocity_ = max_abs_angular_velocity;
44  beta_ = beta;
45  lambda_ = lambda;
46 }
47 
48 // x, y, theta are relative to base location and orientation
49 bool GracefulController::approach(const double x, const double y, const double theta,
50  double& vel_x, double& vel_th, bool backward_motion)
51 {
52  // Distance to goal
53  double r = std::sqrt(x * x + y * y);
54 
55  // Orientation base frame relative to r_
56  double delta = (backward_motion) ? std::atan2(-y, -x) : std::atan2(-y, x);
57 
58  // Determine orientation of goal frame relative to r_
59  double theta2 = angles::normalize_angle(theta + delta);
60 
61  // Compute the virtual control
62  double a = std::atan(-k1_ * theta2);
63  // Compute curvature (k)
64  double k = -1.0/r * (k2_ * (delta - a) + (1 + (k1_/(1+((k1_*theta2)*(k1_*theta2)))))*sin(delta));
65 
66  // Compute max_velocity based on curvature
67  double v = max_abs_velocity_ / (1 + beta_ * std::pow(fabs(k), lambda_));
68  // Limit velocity based on approaching target
69  double approach_limit = std::sqrt(2 * max_decel_ * r);
70  v = std::min(v, approach_limit);
71  v = std::min(std::max(v, min_abs_velocity_), max_abs_velocity_);
72  if (backward_motion)
73  {
74  v *= -1; // reverse linear velocity direction for backward motion
75  }
76 
77  // Compute angular velocity
78  double w = k * v;
79  // Bound angular velocity
80  double bounded_w = std::min(max_abs_angular_velocity_, std::max(-max_abs_angular_velocity_, w));
81  // Make sure that if we reduce w, we reduce v so that kurvature is still followed
82  if (w != 0.0)
83  {
84  v *= (bounded_w/w);
85  }
86 
87  // Send command to base
88  vel_x = v;
89  vel_th = bounded_w;
90  return true;
91 }
92 
94  const double min_abs_velocity,
95  const double max_abs_velocity,
96  const double max_abs_angular_velocity)
97 {
98  min_abs_velocity_ = min_abs_velocity;
99  max_abs_velocity_ = max_abs_velocity;
100  max_abs_angular_velocity_ = max_abs_angular_velocity;
101 }
102 
103 } // namespace graceful_controller
graceful_controller::GracefulController::max_abs_angular_velocity_
double max_abs_angular_velocity_
Definition: graceful_controller.hpp:84
graceful_controller::GracefulController::max_abs_velocity_
double max_abs_velocity_
Definition: graceful_controller.hpp:82
graceful_controller::GracefulController::setVelocityLimits
void setVelocityLimits(const double min_abs_velocity, const double max_abs_velocity, const double max_abs_angular_velocity)
Update the velocity limits.
Definition: graceful_controller.cpp:93
angles::normalize_angle
def normalize_angle(angle)
graceful_controller::GracefulController::max_decel_
double max_decel_
Definition: graceful_controller.hpp:83
graceful_controller::GracefulController::approach
bool approach(const double x, const double y, const double theta, double &vel_x, double &vel_th, bool backward_motion=false)
Implements something loosely based on "A Smooth Control Law for Graceful Motion of Differential Wheel...
Definition: graceful_controller.cpp:49
graceful_controller
Definition: graceful_controller.hpp:26
graceful_controller::GracefulController::min_abs_velocity_
double min_abs_velocity_
Definition: graceful_controller.hpp:81
graceful_controller::GracefulController::GracefulController
GracefulController(double k1, double k2, double min_abs_velocity, double max_abs_velocity, double max_decel, double max_abs_angular_velocity, double beta, double lambda)
Constructor of the controller.
Definition: graceful_controller.cpp:32
graceful_controller::GracefulController::beta_
double beta_
Definition: graceful_controller.hpp:85
graceful_controller::GracefulController::lambda_
double lambda_
Definition: graceful_controller.hpp:86
graceful_controller::GracefulController::k2_
double k2_
Definition: graceful_controller.hpp:80
graceful_controller.hpp
graceful_controller::GracefulController::k1_
double k1_
Definition: graceful_controller.hpp:79
angles.h


graceful_controller
Author(s): Michael Ferguson
autogenerated on Wed Oct 23 2024 02:43:01