39 #include <moveit_msgs/Constraints.h>
40 #include <geometry_msgs/PointStamped.h>
41 #include <geometry_msgs/PoseStamped.h>
42 #include <geometry_msgs/QuaternionStamped.h>
66 moveit_msgs::Constraints
mergeConstraints(
const moveit_msgs::Constraints& first,
const moveit_msgs::Constraints& second);
69 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
bool isEmpty(
const moveit_msgs::Constraints& constr);
87 double tolerance_above);
102 double tolerance = std::numeric_limits<double>::epsilon());
119 moveit_msgs::Constraints
constructGoalConstraints(
const std::string& link_name,
const geometry_msgs::PoseStamped& pose,
120 double tolerance_pos = 1e-3,
double tolerance_angle = 1e-2);
137 moveit_msgs::Constraints
constructGoalConstraints(
const std::string& link_name,
const geometry_msgs::PoseStamped& pose,
138 const std::vector<double>& tolerance_pos,
139 const std::vector<double>& tolerance_angle);
153 const geometry_msgs::QuaternionStamped& quat,
154 double tolerance = 1e-2);
170 const geometry_msgs::Point& reference_point,
171 const geometry_msgs::PointStamped& goal_point,
172 double tolerance = 1e-3);
187 const geometry_msgs::PointStamped& goal_point,
188 double tolerance = 1e-3);