ros2_control - humble
Loading...
Searching...
No Matches
tolerances.hpp
1// Copyright 2013 PAL Robotics S.L.
2// All rights reserved.
3//
4// Software License Agreement (BSD License 2.0)
5// Redistribution and use in source and binary forms, with or without
6// modification, are permitted provided that the following conditions are met:
7// * Redistributions of source code must retain the above copyright notice,
8// this list of conditions and the following disclaimer.
9// * Redistributions in binary form must reproduce the above copyright
10// notice, this list of conditions and the following disclaimer in the
11// documentation and/or other materials provided with the distribution.
12// * Neither the name of PAL Robotics S.L. nor the names of its
13// contributors may be used to endorse or promote products derived from
14// this software without specific prior written permission.
15//
16// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26// POSSIBILITY OF SUCH DAMAGE.
27
29
30#ifndef JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
31#define JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
32
33#include <limits>
34#include <stdexcept>
35#include <string>
36#include <vector>
37
38#include "control_msgs/action/follow_joint_trajectory.hpp"
39#include "joint_trajectory_controller_parameters.hpp"
40
41#include "rclcpp/node.hpp"
42#include "rclcpp/time.hpp"
43
45{
52{
53 double position = 0.0;
54 double velocity = 0.0;
55 double acceleration = 0.0;
56};
57
62{
63 explicit SegmentTolerances(size_t size = 0) : state_tolerance(size), goal_state_tolerance(size) {}
64
66 std::vector<StateTolerances> state_tolerance;
67
69 std::vector<StateTolerances> goal_state_tolerance;
70
72 double goal_time_tolerance = 0.0;
73};
74
96SegmentTolerances get_segment_tolerances(rclcpp::Logger & jtc_logger, const Params & params)
97{
98 auto const & constraints = params.constraints;
99 auto const n_joints = params.joints.size();
100
101 SegmentTolerances tolerances;
102 tolerances.goal_time_tolerance = constraints.goal_time;
103 static auto logger = jtc_logger.get_child("tolerance");
104 RCLCPP_DEBUG(logger, "goal_time %f", constraints.goal_time);
105
106 // State and goal state tolerances
107 tolerances.state_tolerance.resize(n_joints);
108 tolerances.goal_state_tolerance.resize(n_joints);
109 for (size_t i = 0; i < n_joints; ++i)
110 {
111 auto const joint = params.joints[i];
112 tolerances.state_tolerance[i].position = constraints.joints_map.at(joint).trajectory;
113 tolerances.goal_state_tolerance[i].position = constraints.joints_map.at(joint).goal;
114 tolerances.goal_state_tolerance[i].velocity = constraints.stopped_velocity_tolerance;
115
116 RCLCPP_DEBUG(
117 logger, "%s %f", (joint + ".trajectory.position").c_str(),
118 tolerances.state_tolerance[i].position);
119 RCLCPP_DEBUG(
120 logger, "%s %f", (joint + ".goal.position").c_str(),
121 tolerances.goal_state_tolerance[i].position);
122 RCLCPP_DEBUG(
123 logger, "%s %f", (joint + ".goal.velocity").c_str(),
124 tolerances.goal_state_tolerance[i].velocity);
125 }
126
127 return tolerances;
128}
129
130double resolve_tolerance_source(const double default_value, const double goal_value)
131{
132 // from
133 // https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/JointTolerance.msg
134 // There are two special values for tolerances:
135 // * 0 - The tolerance is unspecified and will remain at whatever the default is
136 // * -1 - The tolerance is "erased".
137 // If there was a default, the joint will be allowed to move without restriction.
138 constexpr double ERASE_VALUE = -1.0;
139 auto is_erase_value = [=](double value)
140 { return fabs(value - ERASE_VALUE) < std::numeric_limits<float>::epsilon(); };
141
142 if (goal_value > 0.0)
143 {
144 return goal_value;
145 }
146 else if (is_erase_value(goal_value))
147 {
148 return 0.0;
149 }
150 else if (goal_value < 0.0)
151 {
152 throw std::runtime_error("Illegal tolerance value.");
153 }
154 return default_value;
155}
156
167 rclcpp::Logger & jtc_logger, const SegmentTolerances & default_tolerances,
168 const control_msgs::action::FollowJointTrajectory::Goal & goal,
169 const std::vector<std::string> & joints)
170{
171 SegmentTolerances active_tolerances(default_tolerances);
172 static auto logger = jtc_logger.get_child("tolerance");
173
174 try
175 {
176 active_tolerances.goal_time_tolerance = resolve_tolerance_source(
177 default_tolerances.goal_time_tolerance, rclcpp::Duration(goal.goal_time_tolerance).seconds());
178 }
179 catch (const std::runtime_error & e)
180 {
181 RCLCPP_ERROR_STREAM(
182 logger, "Specified illegal goal_time_tolerance: "
183 << rclcpp::Duration(goal.goal_time_tolerance).seconds()
184 << ". Using default tolerances");
185 return default_tolerances;
186 }
187 RCLCPP_DEBUG(logger, "%s %f", "goal_time", active_tolerances.goal_time_tolerance);
188
189 // State and goal state tolerances
190 for (auto joint_tol : goal.path_tolerance)
191 {
192 auto const joint = joint_tol.name;
193 // map joint names from goal to active_tolerances
194 auto it = std::find(joints.begin(), joints.end(), joint);
195 if (it == joints.end())
196 {
197 RCLCPP_ERROR(
198 logger, "%s",
199 ("joint '" + joint +
200 "' specified in goal.path_tolerance does not exist. "
201 "Using default tolerances.")
202 .c_str());
203 return default_tolerances;
204 }
205 auto i = static_cast<size_t>(std::distance(joints.cbegin(), it));
206 std::string interface = "";
207 try
208 {
209 interface = "position";
210 active_tolerances.state_tolerance[i].position = resolve_tolerance_source(
211 default_tolerances.state_tolerance[i].position, joint_tol.position);
212 interface = "velocity";
213 active_tolerances.state_tolerance[i].velocity = resolve_tolerance_source(
214 default_tolerances.state_tolerance[i].velocity, joint_tol.velocity);
215 interface = "acceleration";
216 active_tolerances.state_tolerance[i].acceleration = resolve_tolerance_source(
217 default_tolerances.state_tolerance[i].acceleration, joint_tol.acceleration);
218 }
219 catch (const std::runtime_error & e)
220 {
221 RCLCPP_ERROR_STREAM(
222 logger, "joint '" << joint << "' specified in goal.path_tolerance has a invalid "
223 << interface << " tolerance. Using default tolerances.");
224 return default_tolerances;
225 }
226
227 RCLCPP_DEBUG(
228 logger, "%s %f", (joint + ".state_tolerance.position").c_str(),
229 active_tolerances.state_tolerance[i].position);
230 RCLCPP_DEBUG(
231 logger, "%s %f", (joint + ".state_tolerance.velocity").c_str(),
232 active_tolerances.state_tolerance[i].velocity);
233 RCLCPP_DEBUG(
234 logger, "%s %f", (joint + ".state_tolerance.acceleration").c_str(),
235 active_tolerances.state_tolerance[i].acceleration);
236 }
237 for (auto goal_tol : goal.goal_tolerance)
238 {
239 auto const joint = goal_tol.name;
240 // map joint names from goal to active_tolerances
241 auto it = std::find(joints.begin(), joints.end(), joint);
242 if (it == joints.end())
243 {
244 RCLCPP_ERROR(
245 logger, "%s",
246 ("joint '" + joint +
247 "' specified in goal.goal_tolerance does not exist. "
248 "Using default tolerances.")
249 .c_str());
250 return default_tolerances;
251 }
252 auto i = static_cast<size_t>(std::distance(joints.cbegin(), it));
253 std::string interface = "";
254 try
255 {
256 interface = "position";
257 active_tolerances.goal_state_tolerance[i].position = resolve_tolerance_source(
258 default_tolerances.goal_state_tolerance[i].position, goal_tol.position);
259 interface = "velocity";
260 active_tolerances.goal_state_tolerance[i].velocity = resolve_tolerance_source(
261 default_tolerances.goal_state_tolerance[i].velocity, goal_tol.velocity);
262 interface = "acceleration";
263 active_tolerances.goal_state_tolerance[i].acceleration = resolve_tolerance_source(
264 default_tolerances.goal_state_tolerance[i].acceleration, goal_tol.acceleration);
265 }
266 catch (const std::runtime_error & e)
267 {
268 RCLCPP_ERROR_STREAM(
269 logger, "joint '" << joint << "' specified in goal.goal_tolerance has a invalid "
270 << interface << " tolerance. Using default tolerances.");
271 return default_tolerances;
272 }
273
274 RCLCPP_DEBUG(
275 logger, "%s %f", (joint + ".goal_state_tolerance.position").c_str(),
276 active_tolerances.goal_state_tolerance[i].position);
277 RCLCPP_DEBUG(
278 logger, "%s %f", (joint + ".goal_state_tolerance.velocity").c_str(),
279 active_tolerances.goal_state_tolerance[i].velocity);
280 RCLCPP_DEBUG(
281 logger, "%s %f", (joint + ".goal_state_tolerance.acceleration").c_str(),
282 active_tolerances.goal_state_tolerance[i].acceleration);
283 }
284
285 return active_tolerances;
286}
287
295inline bool check_state_tolerance_per_joint(
296 const trajectory_msgs::msg::JointTrajectoryPoint & state_error, size_t joint_idx,
297 const StateTolerances & state_tolerance, bool show_errors = false)
298{
299 using std::abs;
300 const double error_position = state_error.positions[joint_idx];
301 const double error_velocity =
302 state_error.velocities.empty() ? 0.0 : state_error.velocities[joint_idx];
303 const double error_acceleration =
304 state_error.accelerations.empty() ? 0.0 : state_error.accelerations[joint_idx];
305
306 const bool is_valid =
307 !(state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) &&
308 !(state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity) &&
309 !(state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration);
310
311 if (is_valid)
312 {
313 return true;
314 }
315
316 if (show_errors)
317 {
318 const auto logger = rclcpp::get_logger("tolerances");
319 RCLCPP_ERROR(logger, "State tolerances failed for joint %d:", joint_idx);
320
321 if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
322 {
323 RCLCPP_ERROR(
324 logger, "Position Error: %f, Position Tolerance: %f", error_position,
325 state_tolerance.position);
326 }
327 if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity)
328 {
329 RCLCPP_ERROR(
330 logger, "Velocity Error: %f, Velocity Tolerance: %f", error_velocity,
331 state_tolerance.velocity);
332 }
333 if (
334 state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration)
335 {
336 RCLCPP_ERROR(
337 logger, "Acceleration Error: %f, Acceleration Tolerance: %f", error_acceleration,
338 state_tolerance.acceleration);
339 }
340 }
341 return false;
342}
343
344} // namespace joint_trajectory_controller
345
346#endif // JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
Definition interpolation_methods.hpp:24
SegmentTolerances get_segment_tolerances(rclcpp::Logger &jtc_logger, const Params &params)
Populate trajectory segment tolerances using data from the ROS node.
Definition tolerances.hpp:96
Trajectory segment tolerances.
Definition tolerances.hpp:62
std::vector< StateTolerances > goal_state_tolerance
Definition tolerances.hpp:69
std::vector< StateTolerances > state_tolerance
Definition tolerances.hpp:66
double goal_time_tolerance
Definition tolerances.hpp:72
Trajectory state tolerances for position, velocity and acceleration variables.
Definition tolerances.hpp:52