ros2_control - rolling
joint_limits.hpp
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 #ifndef JOINT_LIMITS__JOINT_LIMITS_HPP_
18 #define JOINT_LIMITS__JOINT_LIMITS_HPP_
19 
20 #include <limits>
21 #include <sstream>
22 #include <string>
23 
24 namespace joint_limits
25 {
35 {
36  JointLimits()
37  : min_position(std::numeric_limits<double>::quiet_NaN()),
38  max_position(std::numeric_limits<double>::quiet_NaN()),
39  max_velocity(std::numeric_limits<double>::quiet_NaN()),
40  max_acceleration(std::numeric_limits<double>::quiet_NaN()),
41  max_deceleration(std::numeric_limits<double>::quiet_NaN()),
42  max_jerk(std::numeric_limits<double>::quiet_NaN()),
43  max_effort(std::numeric_limits<double>::quiet_NaN()),
44  has_position_limits(false),
45  has_velocity_limits(false),
46  has_acceleration_limits(false),
47  has_deceleration_limits(false),
48  has_jerk_limits(false),
49  has_effort_limits(false),
50  angle_wraparound(false)
51  {
52  }
53 
54  double min_position;
55  double max_position;
56  double max_velocity;
57  double max_acceleration;
58  double max_deceleration;
59  double max_jerk;
60  double max_effort;
61 
62  bool has_position_limits;
63  bool has_velocity_limits;
64  bool has_acceleration_limits;
65  bool has_deceleration_limits;
66  bool has_jerk_limits;
67  bool has_effort_limits;
68  bool angle_wraparound;
69 
70  std::string to_string()
71  {
72  std::stringstream ss_output;
73 
74  ss_output << " has position limits: " << (has_position_limits ? "true" : "false") << " ["
75  << min_position << ", " << max_position << "]\n";
76  ss_output << " has velocity limits: " << (has_velocity_limits ? "true" : "false") << " ["
77  << max_velocity << "]\n";
78  ss_output << " has acceleration limits: " << (has_acceleration_limits ? "true" : "false")
79  << " [" << max_acceleration << "]\n";
80  ss_output << " has deceleration limits: " << (has_deceleration_limits ? "true" : "false")
81  << " [" << max_deceleration << "]\n";
82  ss_output << " has jerk limits: " << (has_jerk_limits ? "true" : "false") << " [" << max_jerk
83  << "]\n";
84  ss_output << " has effort limits: " << (has_effort_limits ? "true" : "false") << " ["
85  << max_effort << "]\n";
86  ss_output << " angle wraparound: " << (angle_wraparound ? "true" : "false");
87 
88  return ss_output.str();
89  }
90 };
91 
113 {
115  : min_position(std::numeric_limits<double>::quiet_NaN()),
116  max_position(std::numeric_limits<double>::quiet_NaN()),
117  k_position(std::numeric_limits<double>::quiet_NaN()),
118  k_velocity(std::numeric_limits<double>::quiet_NaN())
119  {
120  }
121 
122  double min_position;
123  double max_position;
124  double k_position;
125  double k_velocity;
126 
127  std::string to_string()
128  {
129  std::stringstream ss_output;
130 
131  ss_output << " soft position limits: "
132  << "[" << min_position << ", " << max_position << "]\n";
133 
134  ss_output << " k-position: "
135  << "[" << k_position << "]\n";
136 
137  ss_output << " k-velocity: "
138  << "[" << k_velocity << "]\n";
139 
140  return ss_output.str();
141  }
142 };
143 
144 } // namespace joint_limits
145 
146 #endif // JOINT_LIMITS__JOINT_LIMITS_HPP_
Definition: joint_limiter_interface.hpp:31
Definition: joint_limits.hpp:35
Definition: joint_limits.hpp:113