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 #include <moveit/utils/logger.hpp>
44 
45 namespace po = boost::program_options;
46 
47 // Benchmark program measuring time to solve inverse kinematics of robot described in robot_description
48 int main(int argc, char* argv[])
49 {
50  std::string group;
51  std::string tip;
52  unsigned int num;
53  bool reset_to_default;
54  po::options_description desc("Options");
55  // clang-format off
56  desc.add_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).");
64  // clang-format on
65 
66  po::variables_map vm;
67  po::store(po::parse_command_line(argc, argv, desc), vm);
68  po::notify(vm);
69 
70  if (vm.count("help") != 0u)
71  {
72  std::cout << desc << '\n';
73  return 1;
74  }
75 
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);
80  moveit::setNodeLoggerName(node->get_name());
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(node->get_logger(),
110  "No kinematic solver configured for group '" << group->getName() << "' - skipping");
111  continue;
112  }
113 
114  if (tip == "default")
115  {
116  group->getEndEffectorTips(end_effectors);
117  }
118  else
119  {
120  end_effectors = std::vector<std::string>(1, tip);
121  }
122 
123  // perform first IK call to load the cache, so that the time for loading is not included in
124  // average IK call time
125  robot_state.setToDefaultValues();
126  EigenSTL::vector_Isometry3d default_eef_states;
127  for (const auto& end_effector : end_effectors)
128  default_eef_states.push_back(robot_state.getGlobalLinkTransform(end_effector));
129  if (end_effectors.size() == 1)
130  {
131  robot_state.setFromIK(group, default_eef_states[0], end_effectors[0], 0.1);
132  }
133  else
134  {
135  robot_state.setFromIK(group, default_eef_states, end_effectors, 0.1);
136  }
137 
138  bool found_ik;
139  unsigned int num_failed_calls = 0, num_self_collisions = 0;
140  EigenSTL::vector_Isometry3d end_effector_states(end_effectors.size());
141  unsigned int i = 0;
142  while (i < num)
143  {
144  robot_state.setToRandomPositions(group);
145  collision_result.clear();
146  planning_scene.checkSelfCollision(collision_request, collision_result);
147  if (collision_result.collision)
148  {
149  ++num_self_collisions;
150  continue;
151  }
152  for (unsigned j = 0; j < end_effectors.size(); ++j)
153  end_effector_states[j] = robot_state.getGlobalLinkTransform(end_effectors[j]);
154  if (reset_to_default)
155  robot_state.setToDefaultValues();
156  start = std::chrono::system_clock::now();
157  if (end_effectors.size() == 1)
158  {
159  found_ik = robot_state.setFromIK(group, end_effector_states[0], end_effectors[0], 0.1);
160  }
161  else
162  {
163  found_ik = robot_state.setFromIK(group, end_effector_states, end_effectors, 0.1);
164  }
165  ik_time += std::chrono::system_clock::now() - start;
166  if (!found_ik)
167  num_failed_calls++;
168  ++i;
169  if (i % 100 == 0)
170  {
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));
176  }
177  }
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));
181  }
182 
183  rclcpp::shutdown();
184  return 0;
185 }
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:1246
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.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition: logger.cpp:73
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.