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