Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_KINEMATIC_CONSTRAINTS_UTILS_
00038 #define MOVEIT_KINEMATIC_CONSTRAINTS_UTILS_
00039
00040 #include <moveit_msgs/MotionPlanRequest.h>
00041 #include <geometry_msgs/PointStamped.h>
00042 #include <geometry_msgs/PoseStamped.h>
00043 #include <geometry_msgs/QuaternionStamped.h>
00044 #include <moveit/robot_state/robot_state.h>
00045 #include <limits>
00046
00047 namespace kinematic_constraints
00048 {
00049
00063 moveit_msgs::Constraints mergeConstraints(const moveit_msgs::Constraints &first, const moveit_msgs::Constraints &second);
00064
00065
00067 bool isEmpty(const moveit_msgs::Constraints &constr);
00068
00069 std::size_t countIndividualConstraints(const moveit_msgs::Constraints &constr);
00070
00082 moveit_msgs::Constraints constructGoalConstraints(const robot_state::JointStateGroup *jsg,
00083 double tolerance_below, double tolerance_above);
00084
00095 moveit_msgs::Constraints constructGoalConstraints(const robot_state::JointStateGroup *jsg,
00096 double tolerance = std::numeric_limits<double>::epsilon());
00097
00098
00113 moveit_msgs::Constraints constructGoalConstraints(const std::string &link_name, const geometry_msgs::PoseStamped &pose, double tolerance_pos = 1e-3, double tolerance_angle = 1e-2);
00114
00129 moveit_msgs::Constraints constructGoalConstraints(const std::string &link_name, const geometry_msgs::PoseStamped &pose,
00130 const std::vector<double> &tolerance_pos, const std::vector<double> &tolerance_angle);
00131
00143 moveit_msgs::Constraints constructGoalConstraints(const std::string &link_name, const geometry_msgs::QuaternionStamped &quat, double tolerance = 1e-2);
00144
00158 moveit_msgs::Constraints constructGoalConstraints(const std::string &link_name, const geometry_msgs::Point &reference_point, const geometry_msgs::PointStamped &goal_point, double tolerance = 1e-3);
00159
00172 moveit_msgs::Constraints constructGoalConstraints(const std::string &link_name, const geometry_msgs::PointStamped &goal_point, double tolerance = 1e-3);
00173
00174
00175 }
00176
00177 #endif