moveit2
The MoveIt Motion Planning Framework for ROS 2.
RunBenchmark.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, 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: Ryan Luna */
36 
37 #include <string>
38 
41 #include <rclcpp/executors.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
45 #include <rclcpp/node_options.hpp>
46 #include <rclcpp/utilities.hpp>
47 #include <moveit/utils/logger.hpp>
48 
49 using moveit::getLogger;
50 
51 int main(int argc, char** argv)
52 {
53  rclcpp::init(argc, argv);
54  rclcpp::NodeOptions node_options;
55  node_options.allow_undeclared_parameters(true);
56  node_options.automatically_declare_parameters_from_overrides(true);
57  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("moveit_run_benchmark", node_options);
58  moveit::setNodeLoggerName(node->get_name());
59 
60  // Read benchmark options from param server
62  // Setup benchmark server
64 
65  std::vector<std::string> planning_pipelines;
66  options.getPlanningPipelineNames(planning_pipelines);
67  if (!server.initialize(planning_pipelines))
68  {
69  RCLCPP_ERROR(node->get_logger(), "Failed to initialize benchmark server.");
70  rclcpp::shutdown();
71  return 1;
72  }
73 
74  if (options.scene_name.empty())
75  {
76  std::vector<std::string> scene_names;
77  try
78  {
79  warehouse_ros::DatabaseLoader db_loader(node);
80  warehouse_ros::DatabaseConnection::Ptr warehouse_connection = db_loader.loadDatabase();
81  warehouse_connection->setParams(options.hostname, options.port, 20);
82  if (warehouse_connection->connect())
83  {
84  auto planning_scene_storage = moveit_warehouse::PlanningSceneStorage(warehouse_connection);
85  planning_scene_storage.getPlanningSceneNames(scene_names);
86  RCLCPP_INFO(node->get_logger(), "Loaded scene names");
87  }
88  else
89  {
90  RCLCPP_ERROR(node->get_logger(), "Failed to load scene names from DB");
91  rclcpp::shutdown();
92  return 1;
93  }
94  }
95  catch (std::exception& e)
96  {
97  RCLCPP_ERROR(node->get_logger(), "Failed to load scene names from DB: '%s'", e.what());
98  rclcpp::shutdown();
99  return 1;
100  }
101  // Running benchmarks
102  for (const auto& name : scene_names)
103  {
104  options.scene_name = name;
105  if (!server.runBenchmarks(options))
106  {
107  RCLCPP_ERROR(node->get_logger(), "Failed to run all benchmarks");
108  }
109  }
110  }
111  else
112  {
113  if (!server.runBenchmarks(options))
114  {
115  RCLCPP_ERROR(node->get_logger(), "Failed to run all benchmarks");
116  }
117  }
118 
119  RCLCPP_INFO(node->get_logger(), "Finished benchmarking");
120  rclcpp::spin(node);
121  rclcpp::shutdown();
122  return 0;
123 }
int main(int argc, char **argv)
virtual bool runBenchmarks(const BenchmarkOptions &options)
bool initialize(const std::vector< std::string > &plugin_classes)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition: logger.cpp:73
name
Definition: setup.py:7
Options to configure a benchmark experiment. The configuration is provided via ROS2 parameters.