98 auto const & constraints = params.constraints;
99 auto const n_joints = params.joints.size();
103 static auto logger = jtc_logger.get_child(
"tolerance");
104 RCLCPP_DEBUG(logger,
"goal_time %f", constraints.goal_time);
109 for (
size_t i = 0; i < n_joints; ++i)
111 auto const joint = params.joints[i];
112 tolerances.
state_tolerance[i].position = constraints.joints_map.at(joint).trajectory;
117 logger,
"%s %f", (joint +
".trajectory.position").c_str(),
120 logger,
"%s %f", (joint +
".goal.position").c_str(),
123 logger,
"%s %f", (joint +
".goal.velocity").c_str(),
168 const control_msgs::action::FollowJointTrajectory::Goal & goal,
169 const std::vector<std::string> & joints)
172 static auto logger = jtc_logger.get_child(
"tolerance");
177 default_tolerances.
goal_time_tolerance, rclcpp::Duration(goal.goal_time_tolerance).seconds());
179 catch (
const std::runtime_error & e)
182 logger,
"Specified illegal goal_time_tolerance: %f. Using default tolerances",
183 rclcpp::Duration(goal.goal_time_tolerance).seconds());
184 return default_tolerances;
189 for (
auto joint_tol : goal.path_tolerance)
191 auto const joint = joint_tol.name;
193 auto it = std::find(joints.begin(), joints.end(), joint);
194 if (it == joints.end())
199 "' specified in goal.path_tolerance does not exist. "
200 "Using default tolerances.")
202 return default_tolerances;
204 auto i =
static_cast<size_t>(std::distance(joints.cbegin(), it));
205 std::string
interface = "";
208 interface = "position
";
209 active_tolerances.state_tolerance[i].position = resolve_tolerance_source(
210 default_tolerances.state_tolerance[i].position, joint_tol.position);
211 interface = "velocity
";
212 active_tolerances.state_tolerance[i].velocity = resolve_tolerance_source(
213 default_tolerances.state_tolerance[i].velocity, joint_tol.velocity);
214 interface = "acceleration
";
215 active_tolerances.state_tolerance[i].acceleration = resolve_tolerance_source(
216 default_tolerances.state_tolerance[i].acceleration, joint_tol.acceleration);
218 catch (const std::runtime_error & e)
222 "joint '%s
' specified in goal.path_tolerance has a invalid %s tolerance. Using default "
224 joint.c_str(), interface.c_str());
225 return default_tolerances;
229 logger, "%s %f", (joint + ".state_tolerance.position").c_str(),
230 active_tolerances.state_tolerance[i].position);
232 logger, "%s %f", (joint + ".state_tolerance.velocity").c_str(),
233 active_tolerances.state_tolerance[i].velocity);
235 logger, "%s %f", (joint + ".state_tolerance.acceleration").c_str(),
236 active_tolerances.state_tolerance[i].acceleration);
238 for (auto goal_tol : goal.goal_tolerance)
240 auto const joint = goal_tol.name;
241 // map joint names from goal to active_tolerances
242 auto it = std::find(joints.begin(), joints.end(), joint);
243 if (it == joints.end())
248 "' specified in goal.goal_tolerance does not exist. "
249 "Using default tolerances.")
251 return default_tolerances;
253 auto i = static_cast<size_t>(std::distance(joints.cbegin(), it));
254 std::string interface = "";
257 interface = "position";
258 active_tolerances.goal_state_tolerance[i].position = resolve_tolerance_source(
259 default_tolerances.goal_state_tolerance[i].position, goal_tol.position);
260 interface = "velocity";
261 active_tolerances.goal_state_tolerance[i].velocity = resolve_tolerance_source(
262 default_tolerances.goal_state_tolerance[i].velocity, goal_tol.velocity);
263 interface = "acceleration";
264 active_tolerances.goal_state_tolerance[i].acceleration = resolve_tolerance_source(
265 default_tolerances.goal_state_tolerance[i].acceleration, goal_tol.acceleration);
267 catch (const std::runtime_error & e)
271 "joint '%s
' specified in goal.goal_tolerance has a invalid %s tolerance. Using default "
273 joint.c_str(), interface.c_str());
274 return default_tolerances;
278 logger, "%s %f", (joint + ".goal_state_tolerance.position").c_str(),
279 active_tolerances.goal_state_tolerance[i].position);
281 logger, "%s %f", (joint + ".goal_state_tolerance.velocity").c_str(),
282 active_tolerances.goal_state_tolerance[i].velocity);
284 logger, "%s %f", (joint + ".goal_state_tolerance.acceleration").c_str(),
285 active_tolerances.goal_state_tolerance[i].acceleration);
288 return active_tolerances;
298inline bool check_state_tolerance_per_joint(
299 const trajectory_msgs::msg::JointTrajectoryPoint & state_error, size_t joint_idx,
300 const StateTolerances & state_tolerance, bool show_errors = false)
303 const double error_position = state_error.positions[joint_idx];
304 const double error_velocity =
305 state_error.velocities.empty() ? 0.0 : state_error.velocities[joint_idx];
306 const double error_acceleration =
307 state_error.accelerations.empty() ? 0.0 : state_error.accelerations[joint_idx];
309 const bool is_valid =
310 !(state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) &&
311 !(state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity) &&
312 !(state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration);
321 const auto logger = rclcpp::get_logger("tolerances");
322 RCLCPP_ERROR(logger, "State tolerances failed for joint %d:", joint_idx);
324 if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
327 logger, "Position Error: %f, Position Tolerance: %f", error_position,
328 state_tolerance.position);
330 if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity)
333 logger, "Velocity Error: %f, Velocity Tolerance: %f", error_velocity,
334 state_tolerance.velocity);
337 state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration)
340 logger, "Acceleration Error: %f, Acceleration Tolerance: %f", error_acceleration,
341 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:96