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
00038 #ifndef MOVEIT_KINEMATICS_CONSTRAINT_AWARE_
00039 #define MOVEIT_KINEMATICS_CONSTRAINT_AWARE_
00040
00041
00042 #include <boost/shared_ptr.hpp>
00043 #include <boost/function.hpp>
00044
00045
00046 #include <moveit_msgs/GetConstraintAwarePositionIK.h>
00047 #include <geometry_msgs/PoseStamped.h>
00048 #include <moveit_msgs/MoveItErrorCodes.h>
00049 #include <moveit_msgs/Constraints.h>
00050 #include <moveit_msgs/RobotState.h>
00051
00052
00053 #include <moveit/kinematics_base/kinematics_base.h>
00054
00055
00056 #include <moveit/robot_model/robot_model.h>
00057 #include <moveit/robot_state/robot_state.h>
00058 #include <moveit/planning_scene/planning_scene.h>
00059 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00060 #include <moveit/kinematics_constraint_aware/kinematics_request_response.h>
00061
00062 namespace kinematics_constraint_aware
00063 {
00064 class KinematicsConstraintAware;
00065 typedef boost::shared_ptr<KinematicsConstraintAware> KinematicsConstraintAwarePtr;
00066 typedef boost::shared_ptr<const KinematicsConstraintAware> KinematicsConstraintAwareConstPtr;
00067
00071 class KinematicsConstraintAware
00072 {
00073 public:
00079 KinematicsConstraintAware(const robot_model::RobotModelConstPtr& kinematic_model, const std::string& group_name);
00080
00087 bool getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
00088 const kinematics_constraint_aware::KinematicsRequest& request,
00089 kinematics_constraint_aware::KinematicsResponse& response) const;
00090
00097 bool getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
00098 const moveit_msgs::GetConstraintAwarePositionIK::Request& request,
00099 moveit_msgs::GetConstraintAwarePositionIK::Response& response) const;
00100
00101 const std::string& getGroupName() const
00102 {
00103 return group_name_;
00104 }
00105
00106 const robot_model::RobotModelConstPtr& getRobotModel() const
00107 {
00108 return kinematic_model_;
00109 }
00110
00111 private:
00112 EigenSTL::vector_Affine3d transformPoses(const planning_scene::PlanningSceneConstPtr& planning_scene,
00113 const robot_state::RobotState& kinematic_state,
00114 const std::vector<geometry_msgs::PoseStamped>& poses,
00115 const std::string& target_frame) const;
00116
00117 bool convertServiceRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00118 const moveit_msgs::GetConstraintAwarePositionIK::Request& request,
00119 kinematics_constraint_aware::KinematicsRequest& kinematics_request,
00120 kinematics_constraint_aware::KinematicsResponse& kinematics_response) const;
00121
00122 geometry_msgs::Pose getTipFramePose(const planning_scene::PlanningSceneConstPtr& planning_scene,
00123 const robot_state::RobotState& kinematic_state, const geometry_msgs::Pose& pose,
00124 const std::string& link_name, unsigned int sub_group_index) const;
00125
00126 bool validityCallbackFn(const planning_scene::PlanningSceneConstPtr& planning_scene,
00127 const kinematics_constraint_aware::KinematicsRequest& request,
00128 kinematics_constraint_aware::KinematicsResponse& response,
00129 robot_state::JointStateGroup* joint_state_group,
00130 const std::vector<double>& joint_group_variable_values) const;
00131
00132 std::vector<std::string> sub_groups_names_;
00133
00134 robot_model::RobotModelConstPtr kinematic_model_;
00135
00136 const robot_model::JointModelGroup* joint_model_group_;
00137
00138 std::string group_name_;
00139
00140 bool has_sub_groups_;
00141
00142 unsigned int ik_attempts_;
00143 };
00144 }
00145
00146 #endif