Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
kinematic_parameters.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
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 copyright holder 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 HOLDER 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 #ifndef DWB_PLUGINS__KINEMATIC_PARAMETERS_HPP_
36 #define DWB_PLUGINS__KINEMATIC_PARAMETERS_HPP_
37 
38 #include <limits>
39 #include <memory>
40 #include <string>
41 #include <vector>
42 
43 #include "nav2_util/lifecycle_node.hpp"
44 #include "rclcpp/rclcpp.hpp"
45 
46 namespace dwb_plugins
47 {
48 
54 {
55  friend class KinematicsHandler;
56 
57  inline double getMinX() {return min_vel_x_;}
58  inline double getMaxX() {return max_vel_x_;}
59  inline double getAccX() {return acc_lim_x_;}
60  inline double getDecelX() {return decel_lim_x_;}
61 
62  inline double getMinY() {return min_vel_y_;}
63  inline double getMaxY() {return max_vel_y_;}
64  inline double getAccY() {return acc_lim_y_;}
65  inline double getDecelY() {return decel_lim_y_;}
66 
67  inline double getMinSpeedXY() {return min_speed_xy_;}
68  inline double getMaxSpeedXY() {return max_speed_xy_;}
69 
70  inline double getMinTheta() {return -max_vel_theta_;}
71  inline double getMaxTheta() {return max_vel_theta_;}
72  inline double getAccTheta() {return acc_lim_theta_;}
73  inline double getDecelTheta() {return decel_lim_theta_;}
74  inline double getMinSpeedTheta() {return min_speed_theta_;}
75 
76  inline double getMinSpeedXY_SQ() {return min_speed_xy_sq_;}
77  inline double getMaxSpeedXY_SQ() {return max_speed_xy_sq_;}
78 
90  inline bool isValidSpeed(double x, double y, double theta)
91  {
92  double vmag_sq = x * x + y * y;
93  if (max_speed_xy_ >= 0.0 &&
94  vmag_sq > max_speed_xy_sq_ + std::numeric_limits<float>::epsilon())
95  {
96  return false;
97  }
98  if (
99  min_speed_xy_ >= 0.0 && vmag_sq + std::numeric_limits<float>::epsilon() < min_speed_xy_sq_ &&
100  min_speed_theta_ >= 0.0 &&
101  fabs(theta) + std::numeric_limits<float>::epsilon() < min_speed_theta_)
102  {
103  return false;
104  }
105  if (vmag_sq == 0.0 && theta == 0.0) {return false;}
106  return true;
107  }
108 
109 protected:
110  // For parameter descriptions, see cfg/KinematicParams.cfg
111  double min_vel_x_{0};
112  double min_vel_y_{0};
113  double max_vel_x_{0};
114  double max_vel_y_{0};
115  double base_max_vel_x_{0};
116  double base_max_vel_y_{0};
117  double max_vel_theta_{0};
118  double base_max_vel_theta_{0};
119  double min_speed_xy_{0};
120  double max_speed_xy_{0};
121  double base_max_speed_xy_{0};
122  double min_speed_theta_{0};
123  double acc_lim_x_{0};
124  double acc_lim_y_{0};
125  double acc_lim_theta_{0};
126  double decel_lim_x_{0};
127  double decel_lim_y_{0};
128  double decel_lim_theta_{0};
129 
130  // Cached square values of min_speed_xy and max_speed_xy
131  double min_speed_xy_sq_{0};
132  double max_speed_xy_sq_{0};
133 };
134 
140 {
141 public:
144  void initialize(const nav2_util::LifecycleNode::SharedPtr & nh, const std::string & plugin_name);
145 
146  inline KinematicParameters getKinematics() {return *kinematics_.load();}
147 
148  void setSpeedLimit(const double & speed_limit, const bool & percentage);
149 
150  using Ptr = std::shared_ptr<KinematicsHandler>;
151 
152 protected:
153  nav2_util::LifecycleNode::WeakPtr node_;
154  std::atomic<KinematicParameters *> kinematics_;
155 
156  // Dynamic parameters handler
157  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
162  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
163  std::vector<rclcpp::Parameter> parameters);
164  void update_kinematics(KinematicParameters kinematics);
165  std::string plugin_name_;
166 };
167 
168 } // namespace dwb_plugins
169 
170 #endif // DWB_PLUGINS__KINEMATIC_PARAMETERS_HPP_
A class managing the representation of the robot's kinematics.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
A struct containing one representation of the robot's kinematics.
bool isValidSpeed(double x, double y, double theta)
Check to see whether the combined x/y/theta velocities are valid.