ros2_control - galactic
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 <cassert>
34#include <cmath>
35#include <string>
36#include <vector>
37
38#include "control_msgs/action/follow_joint_trajectory.hpp"
39
40#include "rclcpp/node.hpp"
41
43{
50{
51 double position = 0.0;
52 double velocity = 0.0;
53 double acceleration = 0.0;
54};
55
60{
61 explicit SegmentTolerances(size_t size = 0) : state_tolerance(size), goal_state_tolerance(size) {}
62
64 std::vector<StateTolerances> state_tolerance;
65
67 std::vector<StateTolerances> goal_state_tolerance;
68
70 double goal_time_tolerance = 0.0;
71};
72
95 const rclcpp::Node & node, const std::vector<std::string> & joint_names)
96{
97 const auto n_joints = joint_names.size();
98 SegmentTolerances tolerances;
99
100 // State and goal state tolerances
101 double stopped_velocity_tolerance = 0.01;
102 node.get_parameter_or<double>(
103 "constraints.stopped_velocity_tolerance", stopped_velocity_tolerance,
104 stopped_velocity_tolerance);
105
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 const std::string prefix = "constraints." + joint_names[i];
111
112 node.get_parameter_or<double>(
113 prefix + ".trajectory", tolerances.state_tolerance[i].position, 0.0);
114 node.get_parameter_or<double>(
115 prefix + ".goal", tolerances.goal_state_tolerance[i].position, 0.0);
116
117 auto logger = rclcpp::get_logger("tolerance");
118 RCLCPP_DEBUG(
119 logger, "%s %f", (prefix + ".trajectory").c_str(), tolerances.state_tolerance[i].position);
120 RCLCPP_DEBUG(
121 logger, "%s %f", (prefix + ".goal").c_str(), tolerances.goal_state_tolerance[i].position);
122
123 tolerances.goal_state_tolerance[i].velocity = stopped_velocity_tolerance;
124 }
125
126 // Goal time tolerance
127 node.get_parameter_or<double>("constraints.goal_time", tolerances.goal_time_tolerance, 0.0);
128
129 return tolerances;
130}
131
140 const trajectory_msgs::msg::JointTrajectoryPoint & state_error, int joint_idx,
141 const StateTolerances & state_tolerance, bool show_errors = false)
142{
143 using std::abs;
144 const double error_position = state_error.positions[joint_idx];
145 const double error_velocity =
146 state_error.velocities.empty() ? 0.0 : state_error.velocities[joint_idx];
147 const double error_acceleration =
148 state_error.accelerations.empty() ? 0.0 : state_error.accelerations[joint_idx];
149
150 const bool is_valid =
151 !(state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) &&
152 !(state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity) &&
153 !(state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration);
154
155 if (is_valid)
156 {
157 return true;
158 }
159
160 if (show_errors)
161 {
162 const auto logger = rclcpp::get_logger("tolerances");
163 RCLCPP_ERROR(logger, "Path state tolerances failed:");
164
165 if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
166 {
167 RCLCPP_ERROR(
168 logger, "Position Error: %f, Position Tolerance: %f", error_position,
169 state_tolerance.position);
170 }
171 if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity)
172 {
173 RCLCPP_ERROR(
174 logger, "Velocity Error: %f, Velocity Tolerance: %f", error_velocity,
175 state_tolerance.velocity);
176 }
177 if (
178 state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration)
179 {
180 RCLCPP_ERROR(
181 logger, "Acceleration Error: %f, Acceleration Tolerance: %f", error_acceleration,
182 state_tolerance.acceleration);
183 }
184 }
185 return false;
186}
187
188} // namespace joint_trajectory_controller
189
190#endif // JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
Definition joint_trajectory_controller.hpp:58
bool check_state_tolerance_per_joint(const trajectory_msgs::msg::JointTrajectoryPoint &state_error, int joint_idx, const StateTolerances &state_tolerance, bool show_errors=false)
Definition tolerances.hpp:139
SegmentTolerances get_segment_tolerances(const rclcpp::Node &node, const std::vector< std::string > &joint_names)
Populate trajectory segment tolerances using data from the ROS node.
Definition tolerances.hpp:94
Trajectory segment tolerances.
Definition tolerances.hpp:60
std::vector< StateTolerances > goal_state_tolerance
Definition tolerances.hpp:67
std::vector< StateTolerances > state_tolerance
Definition tolerances.hpp:64
double goal_time_tolerance
Definition tolerances.hpp:70
Trajectory state tolerances for position, velocity and acceleration variables.
Definition tolerances.hpp:50