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>
51 int main(
int argc,
char** argv)
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);
65 std::vector<std::string> planning_pipelines;
66 options.getPlanningPipelineNames(planning_pipelines);
69 RCLCPP_ERROR(node->get_logger(),
"Failed to initialize benchmark server.");
76 std::vector<std::string> scene_names;
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())
85 planning_scene_storage.getPlanningSceneNames(scene_names);
86 RCLCPP_INFO(node->get_logger(),
"Loaded scene names");
90 RCLCPP_ERROR(node->get_logger(),
"Failed to load scene names from DB");
95 catch (std::exception& e)
97 RCLCPP_ERROR(node->get_logger(),
"Failed to load scene names from DB: '%s'", e.what());
102 for (
const auto&
name : scene_names)
107 RCLCPP_ERROR(node->get_logger(),
"Failed to run all benchmarks");
115 RCLCPP_ERROR(node->get_logger(),
"Failed to run all benchmarks");
119 RCLCPP_INFO(node->get_logger(),
"Finished benchmarking");
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.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Options to configure a benchmark experiment. The configuration is provided via ROS2 parameters.