3 #ifndef ROBOWFLEX_OMPL_TRAJECTORY 
    4 #define ROBOWFLEX_OMPL_TRAJECTORY 
    9 #include <moveit/robot_trajectory/robot_trajectory.h> 
   12 #include <ompl/geometric/PathGeometric.h> 
   13 #include <ompl/geometric/SimpleSetup.h> 
   55             ompl::geometric::PathGeometric 
toOMPLPath(
const ompl::geometric::SimpleSetupPtr &ss);
 
   61             void fromOMPLPath(
const robot_state::RobotState &reference_state,
 
   62                               const ompl::geometric::PathGeometric &path);
 
#define ROBOWFLEX_CLASS_FORWARD(C)
Macro that forward declares a class and defines two shared ptrs types:
 
OMPLTrajectory provides OMPL path utilities to the Trajectory class.
 
void fromOMPLPath(const robot_state::RobotState &reference_state, const ompl::geometric::PathGeometric &path)
Sets the trajectory from an OMPL Path and a reference state.
 
ompl::geometric::PathGeometric toOMPLPath(const ompl::geometric::SimpleSetupPtr &ss)
Converts to an OMPL Path given an OMPL simple_setup.
 
OMPLTrajectory(const RobotConstPtr &robot, const std::string &group)
Constructor.
 
A const shared pointer wrapper for robowflex::Robot.
 
The Trajectory class is a wrapper around MoveIt!'s robot_trajectory::RobotTrajectory,...
 
Functions for loading and animating robots in Blender.
 
Main namespace. Contains all library classes and functions.
 
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")