75 #ifndef UR_KINEMATICS_PLUGIN_ 76 #define UR_KINEMATICS_PLUGIN_ 83 #include <boost/shared_ptr.hpp> 86 #include <geometry_msgs/PoseStamped.h> 87 #include <moveit_msgs/GetPositionFK.h> 88 #include <moveit_msgs/GetPositionIK.h> 89 #include <moveit_msgs/KinematicSolverInfo.h> 90 #include <moveit_msgs/MoveItErrorCodes.h> 93 #include <kdl/jntarray.hpp> 94 #include <kdl/chainiksolvervel_pinv.hpp> 95 #include <kdl/chainiksolverpos_nr_jl.hpp> 96 #include <kdl/chainfksolverpos_recursive.hpp> 118 virtual bool getPositionIK(
const geometry_msgs::Pose &ik_pose,
119 const std::vector<double> &ik_seed_state,
120 std::vector<double> &solution,
121 moveit_msgs::MoveItErrorCodes &error_code,
125 const std::vector<double> &ik_seed_state,
127 std::vector<double> &solution,
128 moveit_msgs::MoveItErrorCodes &error_code,
132 const std::vector<double> &ik_seed_state,
134 const std::vector<double> &consistency_limits,
135 std::vector<double> &solution,
136 moveit_msgs::MoveItErrorCodes &error_code,
140 const std::vector<double> &ik_seed_state,
142 std::vector<double> &solution,
144 moveit_msgs::MoveItErrorCodes &error_code,
148 const std::vector<double> &ik_seed_state,
150 const std::vector<double> &consistency_limits,
151 std::vector<double> &solution,
153 moveit_msgs::MoveItErrorCodes &error_code,
156 virtual bool getPositionFK(
const std::vector<std::string> &link_names,
157 const std::vector<double> &joint_angles,
158 std::vector<geometry_msgs::Pose> &poses)
const;
160 virtual bool initialize(
const std::string &robot_description,
161 const std::string &group_name,
162 const std::string &base_name,
163 const std::string &tip_name,
164 double search_discretization);
194 const std::vector<double> &ik_seed_state,
196 std::vector<double> &solution,
198 moveit_msgs::MoveItErrorCodes &error_code,
199 const std::vector<double> &consistency_limits,
202 virtual bool setRedundantJoints(
const std::vector<unsigned int> &redundant_joint_indices);
217 const std::vector<double> &consistency_limit,
233 const std::vector<double> &consistency_limits,
235 bool lock_redundancy)
const;
bool isRedundantJoint(unsigned int index) const
robot_state::RobotStatePtr state_2_
int getKDLSegmentIndex(const std::string &name) const
KDL::Chain kdl_tip_chain_
std::vector< double > ik_weights_
KDL::Chain kdl_base_chain_
const std::vector< std::string > & getJointNames() const
Return all the joint names in the order they are used internally.
std::vector< std::string > ur_joint_names_
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
double max_solver_iterations_
robot_model::RobotModelPtr robot_model_
robot_model::JointModelGroup * joint_model_group_
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
bool checkConsistency(const KDL::JntArray &seed_state, const std::vector< double > &consistency_limit, const KDL::JntArray &solution) const
Check whether the solution lies within the consistency limit of the seed state.
std::vector< unsigned int > redundant_joints_map_index_
bool timedOut(const ros::WallTime &start_time, double duration) const
Specific implementation of kinematics using KDL. This version can be used with any robot...
random_numbers::RandomNumberGenerator random_number_generator_
const std::vector< std::string > & getLinkNames() const
Return all the link names in the order they are represented internally.
std::vector< kdl_kinematics_plugin::JointMimic > mimic_joints_
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
moveit_msgs::KinematicSolverInfo fk_chain_info_
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
URKinematicsPlugin()
Default constructor.
std::vector< std::string > ur_link_names_
void getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const
int num_possible_redundant_joints_
robot_state::RobotStatePtr state_
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
moveit_msgs::KinematicSolverInfo ik_chain_info_
int getJointIndex(const std::string &name) const
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)