97 auto const & constraints = params.constraints;
98 auto const n_joints = params.joints.size();
102 static auto logger = jtc_logger.get_child(
"tolerance");
103 RCLCPP_DEBUG(logger,
"goal_time %f", constraints.goal_time);
108 for (
size_t i = 0; i < n_joints; ++i)
110 auto const joint = params.joints[i];
111 tolerances.
state_tolerance[i].position = constraints.joints_map.at(joint).trajectory;
116 logger,
"%s %f", (joint +
".trajectory.position").c_str(),
119 logger,
"%s %f", (joint +
".goal.position").c_str(),
122 logger,
"%s %f", (joint +
".goal.velocity").c_str(),
167 const control_msgs::action::FollowJointTrajectory::Goal & goal,
168 const std::vector<std::string> & joints)
171 static auto logger = jtc_logger.get_child(
"tolerance");
176 default_tolerances.
goal_time_tolerance, rclcpp::Duration(goal.goal_time_tolerance).seconds());
178 catch (
const std::runtime_error & e)
181 logger,
"Specified illegal goal_time_tolerance: %f. Using default tolerances",
182 rclcpp::Duration(goal.goal_time_tolerance).seconds());
183 return default_tolerances;
188 for (
auto joint_tol : goal.path_tolerance)
190 auto const joint = joint_tol.name;
192 auto it = std::find(joints.begin(), joints.end(), joint);
193 if (it == joints.end())
198 "' specified in goal.path_tolerance does not exist. "
199 "Using default tolerances.")
201 return default_tolerances;
203 auto i =
static_cast<size_t>(std::distance(joints.cbegin(), it));
204 std::string
interface = "";
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);
217 catch (const std::runtime_error & e)
221 "joint '%s
' specified in goal.path_tolerance has a invalid %s tolerance. Using default "
223 joint.c_str(), interface.c_str());
224 return default_tolerances;
228 logger, "%s %f", (joint + ".state_tolerance.position").c_str(),
229 active_tolerances.state_tolerance[i].position);
231 logger, "%s %f", (joint + ".state_tolerance.velocity").c_str(),
232 active_tolerances.state_tolerance[i].velocity);
234 logger, "%s %f", (joint + ".state_tolerance.acceleration").c_str(),
235 active_tolerances.state_tolerance[i].acceleration);
237 for (auto goal_tol : goal.goal_tolerance)
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())
247 "' specified in goal.goal_tolerance does not exist. "
248 "Using default tolerances.")
250 return default_tolerances;
252 auto i = static_cast<size_t>(std::distance(joints.cbegin(), it));
253 std::string interface = "";
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);
266 catch (const std::runtime_error & e)
270 "joint '%s
' specified in goal.goal_tolerance has a invalid %s tolerance. Using default "
272 joint.c_str(), interface.c_str());
273 return default_tolerances;
277 logger, "%s %f", (joint + ".goal_state_tolerance.position").c_str(),
278 active_tolerances.goal_state_tolerance[i].position);
280 logger, "%s %f", (joint + ".goal_state_tolerance.velocity").c_str(),
281 active_tolerances.goal_state_tolerance[i].velocity);
283 logger, "%s %f", (joint + ".goal_state_tolerance.acceleration").c_str(),
284 active_tolerances.goal_state_tolerance[i].acceleration);
287 return active_tolerances;
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)
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];
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);
320 const auto logger = rclcpp::get_logger("tolerances");
321 RCLCPP_ERROR(logger, "State tolerances failed for joint %zu:", joint_idx);
323 if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
326 logger, "Position Error: %f, Position Tolerance: %f", error_position,
327 state_tolerance.position);
329 if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity)
332 logger, "Velocity Error: %f, Velocity Tolerance: %f", error_velocity,
333 state_tolerance.velocity);
336 state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration)
339 logger, "Acceleration Error: %f, Acceleration Tolerance: %f", error_acceleration,
340 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:95