1 #ifndef MOVEIT_OPW_KINEMATICS_PLUGIN_ 2 #define MOVEIT_OPW_KINEMATICS_PLUGIN_ 11 #include <geometry_msgs/PoseStamped.h> 12 #include <moveit_msgs/GetPositionFK.h> 13 #include <moveit_msgs/GetPositionIK.h> 14 #include <moveit_msgs/KinematicSolverInfo.h> 15 #include <moveit_msgs/MoveItErrorCodes.h> 53 getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
54 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
58 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
59 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
63 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
64 const std::vector<double>& consistency_limits, std::vector<double>& solution,
65 moveit_msgs::MoveItErrorCodes& error_code,
69 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
70 std::vector<double>& solution,
const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
74 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
75 const std::vector<double>& consistency_limits, std::vector<double>& solution,
76 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
79 virtual bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
80 std::vector<geometry_msgs::Pose>& poses)
const override;
82 virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
83 const std::string& base_name,
const std::string& tip_frame,
double search_discretization)
override 85 std::vector<std::string> tip_frames;
86 tip_frames.push_back(tip_frame);
87 return initialize(robot_description, group_name, base_name, tip_frames, search_discretization);
90 virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
91 const std::string& base_name,
const std::vector<std::string>& tip_frames,
92 double search_discretization)
override;
97 const std::vector<std::string>&
getJointNames()
const override;
102 const std::vector<std::string>&
getLinkNames()
const override;
110 getPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
116 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
117 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
118 moveit_msgs::MoveItErrorCodes& error_code,
const std::vector<double>& consistency_limits,
122 searchPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
123 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
124 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
127 virtual bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
override;
138 static double distance(
const std::vector<double>& a,
const std::vector<double>& b);
140 const std::vector<std::vector<double>>& candidates);
141 bool getAllIK(
const Eigen::Affine3d& pose, std::vector<std::vector<double>>& joint_poses)
const;
142 bool getIK(
const Eigen::Affine3d& pose,
const std::vector<double>& seed_state, std::vector<double>& joint_pose)
const;
154 bool comparePoses(Eigen::Isometry3d& Ta, Eigen::Affine3d& Tb);
static std::size_t closestJointPose(const std::vector< double > &target, const std::vector< std::vector< double >> &candidates)
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool selfTest()
check forward and inverse kinematics consistency
bool comparePoses(Eigen::Isometry3d &Ta, Eigen::Affine3d &Tb)
check if two poses are the same within an absolute tolerance of 1e-6
bool getIK(const Eigen::Affine3d &pose, const std::vector< double > &seed_state, std::vector< double > &joint_pose) const
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
int num_possible_redundant_joints_
robot_state::RobotStatePtr robot_state_
moveit_msgs::KinematicSolverInfo ik_group_info_
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 override
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 override
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) override
bool getAllIK(const Eigen::Affine3d &pose, std::vector< std::vector< double >> &joint_poses) const
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
bool isRedundantJoint(unsigned int index) const
robot_model::JointModelGroup * joint_model_group_
bool operator<(const LimitObeyingSol &a) const
static double distance(const std::vector< double > &a, const std::vector< double > &b)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
robot_model::RobotModelPtr robot_model_
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
std::vector< double > value
bool timedOut(const ros::WallTime &start_time, double duration) const
int getJointIndex(const std::string &name) const
opw_kinematics::Parameters< double > opw_parameters_
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
MoveItOPWKinematicsPlugin()
Default constructor.