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: "
183 << rclcpp::Duration(goal.goal_time_tolerance).seconds()
184 <<
". Using default tolerances");
185 return default_tolerances;
190 for (
auto joint_tol : goal.path_tolerance)
192 auto const joint = joint_tol.name;
194 auto it = std::find(joints.begin(), joints.end(), joint);
195 if (it == joints.end())
200 "' specified in goal.path_tolerance does not exist. "
201 "Using default tolerances.")
203 return default_tolerances;
205 auto i =
static_cast<size_t>(std::distance(joints.cbegin(), it));
206 std::string
interface = "";
209 interface = "position
";
210 active_tolerances.state_tolerance[i].position = resolve_tolerance_source(
211 default_tolerances.state_tolerance[i].position, joint_tol.position);
212 interface = "velocity
";
213 active_tolerances.state_tolerance[i].velocity = resolve_tolerance_source(
214 default_tolerances.state_tolerance[i].velocity, joint_tol.velocity);
215 interface = "acceleration
";
216 active_tolerances.state_tolerance[i].acceleration = resolve_tolerance_source(
217 default_tolerances.state_tolerance[i].acceleration, joint_tol.acceleration);
219 catch (const std::runtime_error & e)
222 logger, "joint '
" << joint << "' specified in goal.path_tolerance has a invalid
"
223 << interface << " tolerance. Using default tolerances.
");
224 return default_tolerances;
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)
269 logger, "joint
'" << joint << "' specified in goal.goal_tolerance has a invalid
"
270 << interface << " tolerance. Using
default tolerances.
");
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 %d:
", 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:96