48int main(
int argc, 
char* argv[])
 
   53  bool reset_to_default;
 
   54  po::options_description desc(
"Options");
 
   57      (
"help", 
"show help message")
 
   58      (
"group", po::value<std::string>(&group)->default_value(
"all"), 
"name of planning group")
 
   59      (
"tip", po::value<std::string>(&tip)->default_value(
"default"), 
"name of the end effector in the planning group")
 
   60      (
"num", po::value<unsigned int>(&num)->default_value(100000), 
"number of IK solutions to compute")
 
   61      (
"reset_to_default", po::value<bool>(&reset_to_default)->default_value(
true),
 
   62       "whether to reset IK seed to default state. If set to false, the seed is the " 
   63       "correct IK solution (to accelerate filling the cache).");
 
   67  po::store(po::parse_command_line(argc, argv, desc), vm);
 
   70  if (vm.count(
"help") != 0u)
 
   72    std::cout << desc << 
'\n';
 
   76  rclcpp::init(argc, argv);
 
   77  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"benchmark_ik");
 
   78  rclcpp::executors::MultiThreadedExecutor executor;
 
   79  executor.add_node(node);
 
   90  std::chrono::duration<double> ik_time(0);
 
   91  std::chrono::time_point<std::chrono::system_clock> start;
 
   92  std::vector<moveit::core::JointModelGroup*> groups;
 
   93  std::vector<std::string> end_effectors;
 
   97    groups = kinematic_model->getJointModelGroups();
 
  101    groups.push_back(kinematic_model->getJointModelGroup(group));
 
  104  for (
const auto& group : groups)
 
  107    if (group->getSolverInstance() == 
nullptr)
 
  109      RCLCPP_WARN_STREAM(node->get_logger(),
 
  110                         "No kinematic solver configured for group '" << group->getName() << 
"' - skipping");
 
  114    if (tip == 
"default")
 
  116      group->getEndEffectorTips(end_effectors);
 
  120      end_effectors = std::vector<std::string>(1, tip);
 
  126    EigenSTL::vector_Isometry3d default_eef_states;
 
  127    for (
const auto& end_effector : end_effectors)
 
  129    if (end_effectors.size() == 1)
 
  131      robot_state.
setFromIK(group, default_eef_states[0], end_effectors[0], 0.1);
 
  135      robot_state.
setFromIK(group, default_eef_states, end_effectors, 0.1);
 
  139    unsigned int num_failed_calls = 0, num_self_collisions = 0;
 
  140    EigenSTL::vector_Isometry3d end_effector_states(end_effectors.size());
 
  145      collision_result.
clear();
 
  146      planning_scene.checkSelfCollision(collision_request, collision_result);
 
  149        ++num_self_collisions;
 
  152      for (
unsigned j = 0; j < end_effectors.size(); ++j)
 
  154      if (reset_to_default)
 
  156      start = std::chrono::system_clock::now();
 
  157      if (end_effectors.size() == 1)
 
  159        found_ik = robot_state.
setFromIK(group, end_effector_states[0], end_effectors[0], 0.1);
 
  163        found_ik = robot_state.
setFromIK(group, end_effector_states, end_effectors, 0.1);
 
  165      ik_time += std::chrono::system_clock::now() - start;
 
  171        RCLCPP_INFO(node->get_logger(),
 
  172                    "Avg. time per IK solver call is %g after %d calls. %g%% of calls failed to return a solution. " 
  173                    "%g%% of random joint configurations were ignored due to self-collisions.",
 
  174                    ik_time.count() / 
static_cast<double>(i), i, 100. * num_failed_calls / i,
 
  175                    100. * num_self_collisions / (num_self_collisions + i));
 
  178    RCLCPP_INFO(node->get_logger(), 
"Summary for group %s: %g %g %g", group->getName().c_str(),
 
  179                ik_time.count() / 
static_cast<double>(i), 100. * num_failed_calls / i,
 
  180                100. * num_self_collisions / (num_self_collisions + i));
 
 
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...