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: "
180 << rclcpp::Duration(goal.goal_time_tolerance).seconds()
181 <<
". Using default tolerances");
182 return default_tolerances;
187 for (
auto joint_tol : goal.path_tolerance)
189 auto const joint = joint_tol.name;
191 auto it = std::find(joints.begin(), joints.end(), joint);
192 if (it == joints.end())
197 "' specified in goal.path_tolerance does not exist. "
198 "Using default tolerances.")
200 return default_tolerances;
202 auto i =
static_cast<size_t>(std::distance(joints.cbegin(), it));
203 std::string
interface = "";
206 interface = "position
";
207 active_tolerances.state_tolerance[i].position = resolve_tolerance_source(
208 default_tolerances.state_tolerance[i].position, joint_tol.position);
209 interface = "velocity
";
210 active_tolerances.state_tolerance[i].velocity = resolve_tolerance_source(
211 default_tolerances.state_tolerance[i].velocity, joint_tol.velocity);
212 interface = "acceleration
";
213 active_tolerances.state_tolerance[i].acceleration = resolve_tolerance_source(
214 default_tolerances.state_tolerance[i].acceleration, joint_tol.acceleration);
216 catch (const std::runtime_error & e)
219 logger, "joint '
" << joint << "' specified in goal.path_tolerance has a invalid
"
220 << interface << " tolerance. Using default tolerances.
");
221 return default_tolerances;
226 active_tolerances.state_tolerance[i].position);
228 logger, "%s %f
", (joint + ".state_tolerance.velocity
").c_str(),
229 active_tolerances.state_tolerance[i].velocity);
231 logger, "%s %f
", (joint + ".state_tolerance.acceleration
").c_str(),
232 active_tolerances.state_tolerance[i].acceleration);
234 for (auto goal_tol : goal.goal_tolerance)
236 auto const joint = goal_tol.name;
237 // map joint names from goal to active_tolerances
238 auto it = std::find(joints.begin(), joints.end(), joint);
239 if (it == joints.end())
244 "' specified in goal.goal_tolerance does not exist.
"
245 "Using
default tolerances.
")
247 return default_tolerances;
249 auto i = static_cast<size_t>(std::distance(joints.cbegin(), it));
250 std::string interface = "";
253 interface = "position
";
254 active_tolerances.goal_state_tolerance[i].position = resolve_tolerance_source(
255 default_tolerances.goal_state_tolerance[i].position, goal_tol.position);
256 interface = "velocity
";
257 active_tolerances.goal_state_tolerance[i].velocity = resolve_tolerance_source(
258 default_tolerances.goal_state_tolerance[i].velocity, goal_tol.velocity);
259 interface = "acceleration
";
260 active_tolerances.goal_state_tolerance[i].acceleration = resolve_tolerance_source(
261 default_tolerances.goal_state_tolerance[i].acceleration, goal_tol.acceleration);
263 catch (const std::runtime_error & e)
266 logger, "joint
'" << joint << "' specified in goal.goal_tolerance has a invalid
"
267 << interface << " tolerance. Using
default tolerances.
");
268 return default_tolerances;
272 logger, "%s %f
", (joint + ".goal_state_tolerance.position
").c_str(),
273 active_tolerances.goal_state_tolerance[i].position);
275 logger, "%s %f
", (joint + ".goal_state_tolerance.velocity
").c_str(),
276 active_tolerances.goal_state_tolerance[i].velocity);
278 logger, "%s %f
", (joint + ".goal_state_tolerance.acceleration
").c_str(),
279 active_tolerances.goal_state_tolerance[i].acceleration);
282 return active_tolerances;
292inline bool check_state_tolerance_per_joint(
293 const trajectory_msgs::msg::JointTrajectoryPoint & state_error, size_t joint_idx,
294 const StateTolerances & state_tolerance, bool show_errors = false)
297 const double error_position = state_error.positions[joint_idx];
298 const double error_velocity =
299 state_error.velocities.empty() ? 0.0 : state_error.velocities[joint_idx];
300 const double error_acceleration =
301 state_error.accelerations.empty() ? 0.0 : state_error.accelerations[joint_idx];
303 const bool is_valid =
304 !(state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) &&
305 !(state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity) &&
306 !(state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration);
315 const auto logger = rclcpp::get_logger("tolerances
");
316 RCLCPP_ERROR(logger, "State tolerances failed
for joint %lu:
", joint_idx);
318 if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
321 logger, "Position Error: %f, Position Tolerance: %f
", error_position,
322 state_tolerance.position);
324 if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity)
327 logger, "Velocity Error: %f, Velocity Tolerance: %f
", error_velocity,
328 state_tolerance.velocity);
331 state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration)
334 logger, "Acceleration Error: %f, Acceleration Tolerance: %f
", error_acceleration,
335 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