Robowflex
v0.1
Making MoveIt Easy
|
#include <tuple>
#include <functional>
#include <moveit/robot_state/robot_state.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit_msgs/RobotTrajectory.h>
#include <robowflex_library/class_forward.h>
Go to the source code of this file.
Classes | |
class | robowflex::Trajectory |
The Trajectory class is a wrapper around MoveIt!'s robot_trajectory::RobotTrajectory, with extra convenience functions such interpolation and collision checking. There are also utilities to load and save trajectories from YAML files (toYAMLFile() and fromYAMLFile()). More... | |
Namespaces | |
robowflex | |
Main namespace. Contains all library classes and functions. | |
Typedefs | |
using | robowflex::PathMetric = std::function< double(const robot_state::RobotState &, const robot_state::RobotState &)> |
A metric over robot states. More... | |