37 #ifndef MOVEIT_MOVE_GROUP_KINEMATICS_SERVICE_CAPABILITY_ 38 #define MOVEIT_MOVE_GROUP_KINEMATICS_SERVICE_CAPABILITY_ 41 #include <moveit_msgs/GetPositionIK.h> 42 #include <moveit_msgs/GetPositionFK.h> 54 bool computeIKService(moveit_msgs::GetPositionIK::Request& req, moveit_msgs::GetPositionIK::Response& res);
55 bool computeFKService(moveit_msgs::GetPositionFK::Request& req, moveit_msgs::GetPositionFK::Response& res);
58 moveit_msgs::PositionIKRequest& req, moveit_msgs::RobotState& solution, moveit_msgs::MoveItErrorCodes& error_code,
59 robot_state::RobotState& rs,
60 const robot_state::GroupStateValidityCallbackFn& constraint = robot_state::GroupStateValidityCallbackFn())
const;
virtual void initialize()
bool computeIKService(moveit_msgs::GetPositionIK::Request &req, moveit_msgs::GetPositionIK::Response &res)
void computeIK(moveit_msgs::PositionIKRequest &req, moveit_msgs::RobotState &solution, moveit_msgs::MoveItErrorCodes &error_code, robot_state::RobotState &rs, const robot_state::GroupStateValidityCallbackFn &constraint=robot_state::GroupStateValidityCallbackFn()) const
ros::ServiceServer ik_service_
ros::ServiceServer fk_service_
MoveGroupKinematicsService()
bool computeFKService(moveit_msgs::GetPositionFK::Request &req, moveit_msgs::GetPositionFK::Response &res)