95 const rclcpp::Node & node,
const std::vector<std::string> & joint_names)
97 const auto n_joints = joint_names.size();
101 double stopped_velocity_tolerance = 0.01;
102 node.get_parameter_or<
double>(
103 "constraints.stopped_velocity_tolerance", stopped_velocity_tolerance,
104 stopped_velocity_tolerance);
108 for (
size_t i = 0; i < n_joints; ++i)
110 const std::string prefix =
"constraints." + joint_names[i];
112 node.get_parameter_or<
double>(
114 node.get_parameter_or<
double>(
117 auto logger = rclcpp::get_logger(
"tolerance");
119 logger,
"%s %f", (prefix +
".trajectory").c_str(), tolerances.
state_tolerance[i].position);
127 node.get_parameter_or<
double>(
"constraints.goal_time", tolerances.
goal_time_tolerance, 0.0);
140 const trajectory_msgs::msg::JointTrajectoryPoint & state_error,
int joint_idx,
144 const double error_position = state_error.positions[joint_idx];
145 const double error_velocity =
146 state_error.velocities.empty() ? 0.0 : state_error.velocities[joint_idx];
147 const double error_acceleration =
148 state_error.accelerations.empty() ? 0.0 : state_error.accelerations[joint_idx];
150 const bool is_valid =
151 !(state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) &&
152 !(state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity) &&
153 !(state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration);
162 const auto logger = rclcpp::get_logger(
"tolerances");
163 RCLCPP_ERROR(logger,
"Path state tolerances failed:");
165 if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
168 logger,
"Position Error: %f, Position Tolerance: %f", error_position,
169 state_tolerance.position);
171 if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity)
174 logger,
"Velocity Error: %f, Velocity Tolerance: %f", error_velocity,
175 state_tolerance.velocity);
178 state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration)
181 logger,
"Acceleration Error: %f, Acceleration Tolerance: %f", error_acceleration,
182 state_tolerance.acceleration);
bool check_state_tolerance_per_joint(const trajectory_msgs::msg::JointTrajectoryPoint &state_error, int joint_idx, const StateTolerances &state_tolerance, bool show_errors=false)
Definition tolerances.hpp:139
SegmentTolerances get_segment_tolerances(const rclcpp::Node &node, const std::vector< std::string > &joint_names)
Populate trajectory segment tolerances using data from the ROS node.
Definition tolerances.hpp:94