moveit2
The MoveIt Motion Planning Framework for ROS 2.
joint_limits.hpp
Go to the documentation of this file.
1 // Copyright 2020 PAL Robotics S.L.
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 
16 
17 #pragma once
18 
19 // TODO(henning): This file is copied from the DRAFT PR https://github.com/ros-controls/ros2_control/pull/462 since the
20 // current ros2_control implementation does not offer the desired joint limits API, yet. Remove when ros2_control has an
21 // upstream version of this.
22 
23 #include <limits>
24 #include <sstream>
25 #include <string>
26 
27 namespace joint_limits
28 {
30 {
32  : min_position(std::numeric_limits<double>::quiet_NaN())
33  , max_position(std::numeric_limits<double>::quiet_NaN())
34  , max_velocity(std::numeric_limits<double>::quiet_NaN())
35  , max_acceleration(std::numeric_limits<double>::quiet_NaN())
36  , max_jerk(std::numeric_limits<double>::quiet_NaN())
37  , max_effort(std::numeric_limits<double>::quiet_NaN())
38  , has_position_limits(false)
39  , has_velocity_limits(false)
41  , has_jerk_limits(false)
42  , has_effort_limits(false)
43  , angle_wraparound(false)
44  {
45  }
46 
47  double min_position;
48  double max_position;
49  double max_velocity;
51  double max_jerk;
52  double max_effort;
53 
60 
61  std::string to_string() // NOLINT: Ignore case style
62  {
63  std::stringstream ss_output;
64 
66  {
67  ss_output << " position limits: "
68  << "[" << min_position << ", " << max_position << "]\n";
69  }
71  {
72  ss_output << " velocity limit: "
73  << "[" << max_velocity << "]\n";
74  }
76  {
77  ss_output << " acceleration limit: "
78  << "[" << max_acceleration << "]\n";
79  }
80  if (has_jerk_limits)
81  {
82  ss_output << " jerk limit: "
83  << "[" << max_acceleration << "]\n";
84  }
86  {
87  ss_output << " effort limit: "
88  << "[" << max_acceleration << "]\n";
89  }
90  if (angle_wraparound)
91  {
92  ss_output << " angle wraparound is active.";
93  }
94 
95  return ss_output.str();
96  }
97 
98  std::string debug_to_string() // NOLINT: Ignore case style
99  {
100  std::stringstream ss_output;
101 
102  ss_output << " has position limits: " << (has_position_limits ? "true" : "false") << "[" << min_position << ", "
103  << max_position << "]\n";
104  ss_output << " has velocity limits: " << (has_velocity_limits ? "true" : "false") << "[" << max_velocity << "]\n";
105  ss_output << " has acceleration limits: " << (has_acceleration_limits ? "true" : "false") << " ["
106  << max_acceleration << "]\n";
107  ss_output << " has jerk limits: " << (has_jerk_limits ? "true" : "false") << "[" << max_jerk << "]\n";
108  ss_output << " has effort limits: " << (has_effort_limits ? "true" : "false") << "[" << max_effort << "]\n";
109  ss_output << " angle wraparound: " << (angle_wraparound ? "true" : "false");
110 
111  return ss_output.str();
112  }
113 };
114 
116 {
118  : min_position(std::numeric_limits<double>::quiet_NaN())
119  , max_position(std::numeric_limits<double>::quiet_NaN())
120  , k_position(std::numeric_limits<double>::quiet_NaN())
121  , k_velocity(std::numeric_limits<double>::quiet_NaN())
122  {
123  }
124 
125  double min_position;
126  double max_position;
127  double k_position;
128  double k_velocity;
129 };
130 
131 } // namespace joint_limits
std::string debug_to_string()