42 #ifndef MOVEIT_ROS_PLANNING_SRV_KINEMATICS_PLUGIN_ 43 #define MOVEIT_ROS_PLANNING_SRV_KINEMATICS_PLUGIN_ 52 #include <geometry_msgs/PoseStamped.h> 53 #include <moveit_msgs/GetPositionFK.h> 54 #include <moveit_msgs/GetPositionIK.h> 55 #include <moveit_msgs/KinematicSolverInfo.h> 56 #include <moveit_msgs/MoveItErrorCodes.h> 78 getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
79 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
83 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
84 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
88 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
89 const std::vector<double>& consistency_limits, std::vector<double>& solution,
90 moveit_msgs::MoveItErrorCodes& error_code,
94 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
95 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
96 moveit_msgs::MoveItErrorCodes& error_code,
100 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
101 const std::vector<double>& consistency_limits, std::vector<double>& solution,
102 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
105 virtual bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
106 std::vector<geometry_msgs::Pose>& poses)
const;
108 virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
109 const std::string& base_name,
const std::string& tip_frame,
double search_discretization)
111 std::vector<std::string> tip_frames;
112 tip_frames.push_back(tip_frame);
113 return initialize(robot_description, group_name, base_name, tip_frames, search_discretization);
116 virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
117 const std::string& base_name,
const std::vector<std::string>& tip_frames,
118 double search_discretization);
137 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
138 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
139 moveit_msgs::MoveItErrorCodes& error_code,
const std::vector<double>& consistency_limits,
143 searchPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
144 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
145 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
148 virtual bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices);
SrvKinematicsPlugin()
Default constructor.
moveit_msgs::KinematicSolverInfo ik_group_info_
const std::vector< std::string > & getJointNames() const
Return all the joint names in the order they are used internally.
int num_possible_redundant_joints_
bool isRedundantJoint(unsigned int index) const
robot_state::RobotStatePtr robot_state_
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_frame, double search_discretization)
std::shared_ptr< ros::ServiceClient > ik_service_client_
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
const std::vector< std::string > & getLinkNames() const
Return all the link names in the order they are represented internally.
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
robot_model::RobotModelPtr robot_model_
robot_model::JointModelGroup * joint_model_group_
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
bool timedOut(const ros::WallTime &start_time, double duration) const
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
int getJointIndex(const std::string &name) const
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...