Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
smooth_control_law.hpp
1 // Copyright (c) 2023 Alberto J. Tudela Roldán
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 #ifndef NAV2_GRACEFUL_CONTROLLER__SMOOTH_CONTROL_LAW_HPP_
16 #define NAV2_GRACEFUL_CONTROLLER__SMOOTH_CONTROL_LAW_HPP_
17 
18 #include <algorithm>
19 #include <string>
20 
21 #include "geometry_msgs/msg/pose.hpp"
22 #include "geometry_msgs/msg/twist.hpp"
23 
24 namespace nav2_graceful_controller
25 {
26 
33 {
34 public:
48  double k_phi, double k_delta, double beta, double lambda, double slowdown_radius,
49  double v_linear_min, double v_linear_max, double v_angular_max);
50 
54  ~SmoothControlLaw() = default;
55 
65  const double k_phi, const double k_delta, const double beta, const double lambda);
66 
72  void setSlowdownRadius(const double slowdown_radius);
73 
81  void setSpeedLimit(
82  const double v_linear_min, const double v_linear_max, const double v_angular_max);
83 
92  geometry_msgs::msg::Twist calculateRegularVelocity(
93  const geometry_msgs::msg::Pose & target,
94  const geometry_msgs::msg::Pose & current,
95  const bool & backward = false);
96 
104  geometry_msgs::msg::Twist calculateRegularVelocity(
105  const geometry_msgs::msg::Pose & target, const bool & backward = false);
106 
117  geometry_msgs::msg::Pose calculateNextPose(
118  const double dt,
119  const geometry_msgs::msg::Pose & target,
120  const geometry_msgs::msg::Pose & current,
121  const bool & backward = false);
122 
123 protected:
133  double calculateCurvature(double r, double phi, double delta);
134 
144  double k_phi_;
145 
154  double k_delta_;
155 
160  double beta_;
161 
166  double lambda_;
167 
172 
177 
182 
187 };
188 
189 } // namespace nav2_graceful_controller
190 
191 #endif // NAV2_GRACEFUL_CONTROLLER__SMOOTH_CONTROL_LAW_HPP_
Smooth control law for graceful motion based on "A smooth control law for graceful motion" (Jong Jin ...
void setCurvatureConstants(const double k_phi, const double k_delta, const double beta, const double lambda)
Set the values that define the curvature.
double calculateCurvature(double r, double phi, double delta)
Calculate the path curvature using a Lyapunov-based feedback control law from "A smooth control law f...
geometry_msgs::msg::Twist calculateRegularVelocity(const geometry_msgs::msg::Pose &target, const geometry_msgs::msg::Pose &current, const bool &backward=false)
Compute linear and angular velocities command using the curvature.
double k_phi_
Ratio of the rate of change in phi to the rate of change in r. Controls the convergence of the slow s...
~SmoothControlLaw()=default
Destructor for nav2_graceful_controller::SmoothControlLaw.
void setSpeedLimit(const double v_linear_min, const double v_linear_max, const double v_angular_max)
Update the velocity limits.
double v_linear_min_
Minimum linear velocity.
geometry_msgs::msg::Pose calculateNextPose(const double dt, const geometry_msgs::msg::Pose &target, const geometry_msgs::msg::Pose &current, const bool &backward=false)
Calculate the next pose of the robot by generating a velocity command using the curvature and the cur...
double v_linear_max_
Maximum linear velocity.
SmoothControlLaw(double k_phi, double k_delta, double beta, double lambda, double slowdown_radius, double v_linear_min, double v_linear_max, double v_angular_max)
Constructor for nav2_graceful_controller::SmoothControlLaw.
void setSlowdownRadius(const double slowdown_radius)
Set the slowdown radius.
double beta_
Constant factor applied to the path curvature. This value must be positive. Determines how fast the v...
double k_delta_
Constant factor applied to the heading error feedback. Controls the convergence of the fast subsystem...
double slowdown_radius_
Radial threshold applied to the slowdown rule.
double lambda_
Constant factor applied to the path curvature. This value must be greater or equal to 1....
double v_angular_max_
Maximum angular velocity.