ros2_control - humble
Loading...
Searching...
No Matches
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
24namespace joint_limits
25{
35{
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_jerk(std::numeric_limits<double>::quiet_NaN()),
42 max_effort(std::numeric_limits<double>::quiet_NaN()),
43 has_position_limits(false),
44 has_velocity_limits(false),
45 has_acceleration_limits(false),
46 has_jerk_limits(false),
47 has_effort_limits(false),
48 angle_wraparound(false)
49 {
50 }
51
52 double min_position;
53 double max_position;
54 double max_velocity;
55 double max_acceleration;
56 double max_jerk;
57 double max_effort;
58
59 bool has_position_limits;
60 bool has_velocity_limits;
61 bool has_acceleration_limits;
62 bool has_jerk_limits;
63 bool has_effort_limits;
64 bool angle_wraparound;
65
66 std::string to_string()
67 {
68 std::stringstream ss_output;
69
70 ss_output << " has position limits: " << (has_position_limits ? "true" : "false") << " ["
71 << min_position << ", " << max_position << "]\n";
72 ss_output << " has velocity limits: " << (has_velocity_limits ? "true" : "false") << " ["
73 << max_velocity << "]\n";
74 ss_output << " has acceleration limits: " << (has_acceleration_limits ? "true" : "false")
75 << " [" << max_acceleration << "]\n";
76 ss_output << " has jerk limits: " << (has_jerk_limits ? "true" : "false") << " [" << max_jerk
77 << "]\n";
78 ss_output << " has effort limits: " << (has_effort_limits ? "true" : "false") << " ["
79 << max_effort << "]\n";
80 ss_output << " angle wraparound: " << (angle_wraparound ? "true" : "false");
81
82 return ss_output.str();
83 }
84};
85
107{
109 : min_position(std::numeric_limits<double>::quiet_NaN()),
110 max_position(std::numeric_limits<double>::quiet_NaN()),
111 k_position(std::numeric_limits<double>::quiet_NaN()),
112 k_velocity(std::numeric_limits<double>::quiet_NaN())
113 {
114 }
115
116 double min_position;
117 double max_position;
118 double k_position;
119 double k_velocity;
120
121 std::string to_string()
122 {
123 std::stringstream ss_output;
124
125 ss_output << " soft position limits: "
126 << "[" << min_position << ", " << max_position << "]\n";
127
128 ss_output << " k-position: "
129 << "[" << k_position << "]\n";
130
131 ss_output << " k-velocity: "
132 << "[" << k_velocity << "]\n";
133
134 return ss_output.str();
135 }
136};
137
138} // namespace joint_limits
139
140#endif // JOINT_LIMITS__JOINT_LIMITS_HPP_
Definition joint_limits.hpp:25
Definition joint_limits.hpp:35
Definition joint_limits.hpp:107