moveit2
The MoveIt Motion Planning Framework for ROS 2.
benchmark_ik.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Rice University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Rice University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Mark Moll */
36 
37 #include <chrono>
38 #include <rclcpp/rclcpp.hpp>
39 #include <boost/program_options.hpp>
43 
44 namespace po = boost::program_options;
45 
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("cached_ik.measure_ik_call_cost");
47 
48 // Benchmark program measuring time to solve inverse kinematics of robot described in robot_description
49 int main(int argc, char* argv[])
50 {
51  std::string group;
52  std::string tip;
53  unsigned int num;
54  bool reset_to_default;
55  po::options_description desc("Options");
56  // clang-format off
57  desc.add_options()
58  ("help", "show help message")
59  ("group", po::value<std::string>(&group)->default_value("all"), "name of planning group")
60  ("tip", po::value<std::string>(&tip)->default_value("default"), "name of the end effector in the planning group")
61  ("num", po::value<unsigned int>(&num)->default_value(100000), "number of IK solutions to compute")
62  ("reset_to_default", po::value<bool>(&reset_to_default)->default_value(true),
63  "whether to reset IK seed to default state. If set to false, the seed is the "
64  "correct IK solution (to accelerate filling the cache).");
65  // clang-format on
66 
67  po::variables_map vm;
68  po::store(po::parse_command_line(argc, argv, desc), vm);
69  po::notify(vm);
70 
71  if (vm.count("help") != 0u)
72  {
73  std::cout << desc << '\n';
74  return 1;
75  }
76 
77  rclcpp::init(argc, argv);
78  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("benchmark_ik");
79  rclcpp::executors::MultiThreadedExecutor executor;
80  executor.add_node(node);
81 
82  // TODO(henningkayser): Load robot model from robot_description, fix kinematic param config
83  // robot_model_loader::RobotModelLoader robot_model_loader(node);
84  // const moveit::core::RobotModelPtr& kinematic_model = robot_model_loader.getModel();
85  const moveit::core::RobotModelPtr& kinematic_model = moveit::core::loadTestingRobotModel("panda");
87  moveit::core::RobotState& robot_state = planning_scene.getCurrentStateNonConst();
88  collision_detection::CollisionRequest collision_request;
89  collision_detection::CollisionResult collision_result;
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;
94 
95  if (group == "all")
96  {
97  groups = kinematic_model->getJointModelGroups();
98  }
99  else
100  {
101  groups.push_back(kinematic_model->getJointModelGroup(group));
102  }
103 
104  for (const auto& group : groups)
105  {
106  // skip group if there's no IK solver
107  if (group->getSolverInstance() == nullptr)
108  {
109  RCLCPP_WARN_STREAM(LOGGER, "No kinematic solver configured for group '" << group->getName() << "' - skipping");
110  continue;
111  }
112 
113  if (tip == "default")
114  {
115  group->getEndEffectorTips(end_effectors);
116  }
117  else
118  {
119  end_effectors = std::vector<std::string>(1, tip);
120  }
121 
122  // perform first IK call to load the cache, so that the time for loading is not included in
123  // average IK call time
124  robot_state.setToDefaultValues();
125  EigenSTL::vector_Isometry3d default_eef_states;
126  for (const auto& end_effector : end_effectors)
127  default_eef_states.push_back(robot_state.getGlobalLinkTransform(end_effector));
128  if (end_effectors.size() == 1)
129  {
130  robot_state.setFromIK(group, default_eef_states[0], end_effectors[0], 0.1);
131  }
132  else
133  {
134  robot_state.setFromIK(group, default_eef_states, end_effectors, 0.1);
135  }
136 
137  bool found_ik;
138  unsigned int num_failed_calls = 0, num_self_collisions = 0;
139  EigenSTL::vector_Isometry3d end_effector_states(end_effectors.size());
140  unsigned int i = 0;
141  while (i < num)
142  {
143  robot_state.setToRandomPositions(group);
144  collision_result.clear();
145  planning_scene.checkSelfCollision(collision_request, collision_result);
146  if (collision_result.collision)
147  {
148  ++num_self_collisions;
149  continue;
150  }
151  for (unsigned j = 0; j < end_effectors.size(); ++j)
152  end_effector_states[j] = robot_state.getGlobalLinkTransform(end_effectors[j]);
153  if (reset_to_default)
154  robot_state.setToDefaultValues();
155  start = std::chrono::system_clock::now();
156  if (end_effectors.size() == 1)
157  {
158  found_ik = robot_state.setFromIK(group, end_effector_states[0], end_effectors[0], 0.1);
159  }
160  else
161  {
162  found_ik = robot_state.setFromIK(group, end_effector_states, end_effectors, 0.1);
163  }
164  ik_time += std::chrono::system_clock::now() - start;
165  if (!found_ik)
166  num_failed_calls++;
167  ++i;
168  if (i % 100 == 0)
169  {
170  RCLCPP_INFO(LOGGER,
171  "Avg. time per IK solver call is %g after %d calls. %g%% of calls failed to return a solution. "
172  "%g%% of random joint configurations were ignored due to self-collisions.",
173  ik_time.count() / static_cast<double>(i), i, 100. * num_failed_calls / i,
174  100. * num_self_collisions / (num_self_collisions + i));
175  }
176  }
177  RCLCPP_INFO(LOGGER, "Summary for group %s: %g %g %g", group->getName().c_str(),
178  ik_time.count() / static_cast<double>(i), 100. * num_failed_calls / i,
179  100. * num_self_collisions / (num_self_collisions + i));
180  }
181 
182  rclcpp::shutdown();
183  return 0;
184 }
int main(int argc, char *argv[])
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1271
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
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...
This class maintains the representation of the environment as seen by a planning instance....
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
This namespace includes the central class for representing planning contexts.
Representation of a collision checking request.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.