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>
48 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.benchmarks.RunBenchmark");
50 int main(
int argc,
char** argv)
52 rclcpp::init(argc, argv);
53 rclcpp::NodeOptions node_options;
54 node_options.allow_undeclared_parameters(
true);
55 node_options.automatically_declare_parameters_from_overrides(
true);
56 rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"moveit_run_benchmark", node_options);
63 std::vector<std::string> planning_pipelines;
69 RCLCPP_ERROR(LOGGER,
"Failed to run all benchmarks");
int main(int argc, char **argv)
virtual bool runBenchmarks(const BenchmarkOptions &opts)
void initialize(const std::vector< std::string > &plugin_classes)
void getPlanningPipelineNames(std::vector< std::string > &planning_pipeline_names) const
Get all planning pipeline names.
const rclcpp::Logger LOGGER