38 #include <geometry_msgs/PoseStamped.h> 57 PR2ArmKinematicsPlugin::PR2ArmKinematicsPlugin():active_(false){}
67 const std::string& group_name,
68 const std::string& base_frame,
69 const std::string& tip_frame,
70 double search_discretization)
72 setValues(robot_description, group_name, base_frame, tip_frame, search_discretization);
77 while(!
loadRobotModel(private_handle,robot_model,xml_string) && private_handle.ok())
79 ROS_ERROR(
"Could not load robot model. Are you sure the robot model is on the parameter server?");
91 private_handle.param<
int>(
"free_angle",
free_angle_,2);
118 ROS_DEBUG(
"PR2KinematicsPlugin::active for %s",group_name.c_str());
126 const std::vector<double> &ik_seed_state,
127 std::vector<double> &solution,
128 moveit_msgs::MoveItErrorCodes &error_code,
134 error_code.val = error_code.NO_IK_SOLUTION;
147 jnt_pos_in(i) = ik_seed_state[i];
155 error_code.val = error_code.NO_IK_SOLUTION;
161 solution.resize(dimension_);
164 solution[i] = jnt_pos_out(i);
166 error_code.val = error_code.SUCCESS;
171 ROS_DEBUG(
"An IK solution could not be found");
172 error_code.val = error_code.NO_IK_SOLUTION;
178 const std::vector<double> &ik_seed_state,
180 std::vector<double> &solution,
181 moveit_msgs::MoveItErrorCodes &error_code,
185 static std::vector<double> consistency_limits;
186 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
190 const std::vector<double> &ik_seed_state,
192 const std::vector<double> &consistency_limits,
193 std::vector<double> &solution,
194 moveit_msgs::MoveItErrorCodes &error_code,
198 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
202 const std::vector<double> &ik_seed_state,
204 std::vector<double> &solution,
206 moveit_msgs::MoveItErrorCodes &error_code,
209 static std::vector<double> consistency_limits;
210 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
214 const std::vector<double> &ik_seed_state,
216 const std::vector<double> &consistency_limits,
217 std::vector<double> &solution,
219 moveit_msgs::MoveItErrorCodes &error_code,
225 error_code.val = error_code.FAILURE;
228 if(!consistency_limits.empty() && consistency_limits.size() !=
dimension_)
230 ROS_ERROR(
"Consistency limits should be of size: %d",dimension_);
231 error_code.val = error_code.FAILURE;
241 jnt_pos_in.
resize(dimension_);
244 jnt_pos_in(i) = ik_seed_state[i];
248 if(consistency_limits.empty())
256 boost::bind(solution_callback, _1, _2, _3):
265 consistency_limits[free_angle_],
268 boost::bind(solution_callback, _1, _2, _3):
277 solution.resize(dimension_);
280 solution[i] = jnt_pos_out(i);
286 ROS_DEBUG(
"An IK solution could not be found");
292 const std::vector<double> &joint_angles,
293 std::vector<geometry_msgs::Pose> &poses)
const 303 geometry_msgs::PoseStamped pose;
306 jnt_pos_in.
resize(dimension_);
309 jnt_pos_in(i) = joint_angles[i];
313 poses.
resize(link_names.size());
316 for(
unsigned int i=0; i < poses.size(); i++)
325 ROS_ERROR(
"Could not compute FK for %s",link_names[i].c_str());
const std::vector< std::string > & getJointNames() const
Namespace for the PR2ArmKinematics.
const std::vector< std::string > & getLinkNames() const
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
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 fk_solver_info_
static const int NO_IK_SOLUTION
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
PLUGINLIB_EXPORT_CLASS(pr2_arm_kinematics::PR2ArmKinematicsPlugin, kinematics::KinematicsBase)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
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
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
def xml_string(rootXml, addHeader=True)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
moveit_msgs::KinematicSolverInfo ik_solver_info_
void resize(unsigned int newSize)
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
double search_discretization_
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)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)