95 auto const & constraints = params.constraints;
96 auto const n_joints = params.joints.size();
100 static auto logger = jtc_logger.get_child(
"tolerance");
101 RCLCPP_DEBUG(logger,
"goal_time %f", constraints.goal_time);
106 for (
size_t i = 0; i < n_joints; ++i)
108 auto const joint = params.joints[i];
109 tolerances.
state_tolerance[i].position = constraints.joints_map.at(joint).trajectory;
114 logger,
"%s %f", (joint +
".trajectory.position").c_str(),
117 logger,
"%s %f", (joint +
".goal.position").c_str(),
120 logger,
"%s %f", (joint +
".goal.velocity").c_str(),
165 const control_msgs::action::FollowJointTrajectory::Goal & goal,
166 const std::vector<std::string> & joints)
169 static auto logger = jtc_logger.get_child(
"tolerance");
174 default_tolerances.
goal_time_tolerance, rclcpp::Duration(goal.goal_time_tolerance).seconds());
176 catch (
const std::runtime_error & e)
179 logger,
"Specified illegal goal_time_tolerance: %f. Using default tolerances",
180 rclcpp::Duration(goal.goal_time_tolerance).seconds());
181 return default_tolerances;
186 for (
auto joint_tol : goal.path_tolerance)
188 auto const joint = joint_tol.name;
190 auto it = std::find(joints.begin(), joints.end(), joint);
191 if (it == joints.end())
196 "' specified in goal.path_tolerance does not exist. "
197 "Using default tolerances.")
199 return default_tolerances;
201 auto i =
static_cast<size_t>(std::distance(joints.cbegin(), it));
202 std::string
interface = "";
205 interface = "position
";
206 active_tolerances.state_tolerance[i].position = resolve_tolerance_source(
207 default_tolerances.state_tolerance[i].position, joint_tol.position);
208 interface = "velocity
";
209 active_tolerances.state_tolerance[i].velocity = resolve_tolerance_source(
210 default_tolerances.state_tolerance[i].velocity, joint_tol.velocity);
211 interface = "acceleration
";
212 active_tolerances.state_tolerance[i].acceleration = resolve_tolerance_source(
213 default_tolerances.state_tolerance[i].acceleration, joint_tol.acceleration);
215 catch (const std::runtime_error & e)
219 "joint '%s
' specified in goal.path_tolerance has a invalid %s tolerance. Using default "
221 joint.c_str(), interface.c_str());
222 return default_tolerances;
226 logger, "%s %f", (joint + ".state_tolerance.position").c_str(),
227 active_tolerances.state_tolerance[i].position);
229 logger, "%s %f", (joint + ".state_tolerance.velocity").c_str(),
230 active_tolerances.state_tolerance[i].velocity);
232 logger, "%s %f", (joint + ".state_tolerance.acceleration").c_str(),
233 active_tolerances.state_tolerance[i].acceleration);
235 for (auto goal_tol : goal.goal_tolerance)
237 auto const joint = goal_tol.name;
238 // map joint names from goal to active_tolerances
239 auto it = std::find(joints.begin(), joints.end(), joint);
240 if (it == joints.end())
245 "' specified in goal.goal_tolerance does not exist. "
246 "Using default tolerances.")
248 return default_tolerances;
250 auto i = static_cast<size_t>(std::distance(joints.cbegin(), it));
251 std::string interface = "";
254 interface = "position";
255 active_tolerances.goal_state_tolerance[i].position = resolve_tolerance_source(
256 default_tolerances.goal_state_tolerance[i].position, goal_tol.position);
257 interface = "velocity";
258 active_tolerances.goal_state_tolerance[i].velocity = resolve_tolerance_source(
259 default_tolerances.goal_state_tolerance[i].velocity, goal_tol.velocity);
260 interface = "acceleration";
261 active_tolerances.goal_state_tolerance[i].acceleration = resolve_tolerance_source(
262 default_tolerances.goal_state_tolerance[i].acceleration, goal_tol.acceleration);
264 catch (const std::runtime_error & e)
268 "joint '%s
' specified in goal.goal_tolerance has a invalid %s tolerance. Using default "
270 joint.c_str(), interface.c_str());
271 return default_tolerances;
275 logger, "%s %f", (joint + ".goal_state_tolerance.position").c_str(),
276 active_tolerances.goal_state_tolerance[i].position);
278 logger, "%s %f", (joint + ".goal_state_tolerance.velocity").c_str(),
279 active_tolerances.goal_state_tolerance[i].velocity);
281 logger, "%s %f", (joint + ".goal_state_tolerance.acceleration").c_str(),
282 active_tolerances.goal_state_tolerance[i].acceleration);
285 return active_tolerances;
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)
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];
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);
318 const auto logger = rclcpp::get_logger("tolerances");
319 RCLCPP_ERROR(logger, "State tolerances failed for joint %lu:", joint_idx);
321 if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
324 logger, "Position Error: %f, Position Tolerance: %f", error_position,
325 state_tolerance.position);
327 if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity)
330 logger, "Velocity Error: %f, Velocity Tolerance: %f", error_velocity,
331 state_tolerance.velocity);
334 state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration)
337 logger, "Acceleration Error: %f, Acceleration Tolerance: %f", error_acceleration,
338 state_tolerance.acceleration);
SegmentTolerances get_segment_tolerances(rclcpp::Logger &jtc_logger, const Params ¶ms)
Populate trajectory segment tolerances using data from the ROS node.
Definition tolerances.hpp:93