Function pilz_industrial_motion_planner::computePoseIK(const planning_scene::PlanningSceneConstPtr&, const std::string&, const std::string&, const Eigen::Isometry3d&, const std::string&, const std::map<std::string, double>&, std::map<std::string, double>&, bool, const double)

Function Documentation

bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map<std::string, double> &seed, std::map<std::string, double> &solution, bool check_self_collision = true, const double timeout = 0.0)

compute the inverse kinematics of a given pose, also check robot self collision

Parameters:
  • scene – planning scene

  • group_name – name of planning group

  • link_name – name of target link

  • pose – target pose in IK solver Frame

  • frame_id – reference frame of the target pose

  • seed – seed state of IK solver

  • solution – solution of IK

  • check_self_collision – true to enable self collision checking after IK computation

  • timeout – timeout for IK, if not set the default solver timeout is used

Returns:

true if succeed