38 #ifndef MOVEIT_KINEMATICS_CONSTRAINT_AWARE_ 39 #define MOVEIT_KINEMATICS_CONSTRAINT_AWARE_ 42 #include <boost/shared_ptr.hpp> 43 #include <boost/function.hpp> 46 #include <moveit_msgs/GetConstraintAwarePositionIK.h> 47 #include <geometry_msgs/PoseStamped.h> 48 #include <moveit_msgs/MoveItErrorCodes.h> 49 #include <moveit_msgs/Constraints.h> 50 #include <moveit_msgs/RobotState.h> 53 #include <moveit/kinematics_base/kinematics_base.h> 56 #include <moveit/robot_model/robot_model.h> 57 #include <moveit/robot_state/robot_state.h> 58 #include <moveit/planning_scene/planning_scene.h> 59 #include <moveit/kinematic_constraints/kinematic_constraint.h> 87 bool getIK(
const planning_scene::PlanningSceneConstPtr& planning_scene,
97 bool getIK(
const planning_scene::PlanningSceneConstPtr& planning_scene,
98 const moveit_msgs::GetConstraintAwarePositionIK::Request& request,
99 moveit_msgs::GetConstraintAwarePositionIK::Response& response)
const;
112 EigenSTL::vector_Affine3d
transformPoses(
const planning_scene::PlanningSceneConstPtr& planning_scene,
113 const robot_state::RobotState& kinematic_state,
114 const std::vector<geometry_msgs::PoseStamped>& poses,
115 const std::string& target_frame)
const;
118 const moveit_msgs::GetConstraintAwarePositionIK::Request& request,
122 geometry_msgs::Pose
getTipFramePose(
const planning_scene::PlanningSceneConstPtr& planning_scene,
123 const robot_state::RobotState& kinematic_state,
const geometry_msgs::Pose& pose,
124 const std::string& link_name,
unsigned int sub_group_index)
const;
129 robot_state::JointStateGroup* joint_state_group,
130 const std::vector<double>& joint_group_variable_values)
const;
robot_model::RobotModelConstPtr kinematic_model_
unsigned int ik_attempts_
const std::string & getGroupName() const
std::vector< std::string > sub_groups_names_
EigenSTL::vector_Affine3d transformPoses(const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_state::RobotState &kinematic_state, const std::vector< geometry_msgs::PoseStamped > &poses, const std::string &target_frame) const
boost::shared_ptr< KinematicsConstraintAware > KinematicsConstraintAwarePtr
const robot_model::RobotModelConstPtr & getRobotModel() const
boost::shared_ptr< const KinematicsConstraintAware > KinematicsConstraintAwareConstPtr
bool convertServiceRequest(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetConstraintAwarePositionIK::Request &request, kinematics_constraint_aware::KinematicsRequest &kinematics_request, kinematics_constraint_aware::KinematicsResponse &kinematics_response) const
const robot_model::JointModelGroup * joint_model_group_
bool getIK(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
Solve the planning problem.
bool validityCallbackFn(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response, robot_state::JointStateGroup *joint_state_group, const std::vector< double > &joint_group_variable_values) const
geometry_msgs::Pose getTipFramePose(const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_state::RobotState &kinematic_state, const geometry_msgs::Pose &pose, const std::string &link_name, unsigned int sub_group_index) const
KinematicsConstraintAware(const robot_model::RobotModelConstPtr &kinematic_model, const std::string &group_name)
Default constructor.