|
Robowflex
v0.1
Making MoveIt Easy
|
#include <cstdint>#include <string>#include <vector>#include <tuple>#include <map>#include <fstream>#include <boost/variant.hpp>#include <moveit_msgs/RobotTrajectory.h>#include <moveit/planning_interface/planning_response.h>#include <robowflex_library/class_forward.h>#include <robowflex_library/io/bag.h>#include <robowflex_library/planning.h>Go to the source code of this file.
Classes | |
| struct | robowflex::PlanningQuery |
| A container structure for all elements needed in a planning query, plus an identifying name. More... | |
| class | robowflex::PlanData |
| Detailed statistics and metrics computed from profiling a planner's motion planning. More... | |
| class | robowflex::PlanDataSet |
| Detailed statistics about a benchmark of multiple queries. More... | |
| class | robowflex::Profiler |
| struct | robowflex::Profiler::Options |
| Options for profiling. More... | |
| class | robowflex::Experiment |
| A helper class for benchmarking that controls running multiple queries. More... | |
| class | robowflex::PlanDataSetOutputter |
| An abstract class for outputting benchmark results. More... | |
| class | robowflex::JSONPlanDataSetOutputter |
| A benchmark outputter for storing data in a single JSON file. More... | |
| class | robowflex::TrajectoryPlanDataSetOutputter |
| Benchmark outputter that saves each trajectory from each run to a rosbag file. More... | |
| class | robowflex::OMPLPlanDataSetOutputter |
Benchmark outputter that saves results into OMPL benchmarking log files. If ompl_benchmark_statistics.py is available in your PATH variable, the results are also compiled into a database file. More... | |
Namespaces | |
| robowflex | |
| Main namespace. Contains all library classes and functions. | |
Typedefs | |
| using | robowflex::PlannerMetric = boost::variant< bool, double, int, std::size_t, std::string > |
| Variant type of possible values a run metric could be. More... | |
Functions | |
| std::string | robowflex::toMetricString (const PlannerMetric &metric) |
| Convert a planner metric into a string. More... | |