Robowflex  v0.1
Making MoveIt Easy
ompl_trajectory.h
Go to the documentation of this file.
1 /* Author: Constantinos Chamzas */
2 
3 #ifndef ROBOWFLEX_OMPL_TRAJECTORY
4 #define ROBOWFLEX_OMPL_TRAJECTORY
5 
7 
8 // Moveit
9 #include <moveit/robot_trajectory/robot_trajectory.h>
10 
11 // OMPL
12 #include <ompl/geometric/PathGeometric.h>
13 #include <ompl/geometric/SimpleSetup.h>
14 
15 namespace robowflex
16 {
17  /** \cond IGNORE */
20  ROBOWFLEX_CLASS_FORWARD(Trajectory);
21  /** \endcond */
22 
23  namespace OMPL
24  {
25  /** \cond IGNORE */
26  ROBOWFLEX_CLASS_FORWARD(OMPLTrajectory);
27  /** \endcond */
28 
29  /** \class robowflex::OMPL::OMPLTrajectoryPtr
30  \brief A shared pointer wrapper for robowflex::OMPL::OMPLTrajectory. */
31 
32  /** \class robowflex::OMPL::OMPLTrajectoryConstPtr
33  \brief A const shared pointer wrapper for robowflex::OMPL::OMPLTrajectory. */
34 
35  /** \brief OMPLTrajectory provides OMPL path utilities to the Trajectory class.
36  */
37  class OMPLTrajectory : public Trajectory
38  {
39  public:
40  /** \brief Constructor.
41  * \param[in] robot Robot to construct trajectory for.
42  * \param[in] group Planning group of the trajectory.
43  */
44  OMPLTrajectory(const RobotConstPtr &robot, const std::string &group);
45 
46  /** \brief Constructor.
47  * \param[in] trajectory Trajectory to initialize with.
48  */
50 
51  /** \brief Converts to an OMPL Path given an OMPL \a simple_setup.
52  * \param[in] ss a simple setup structure that has the correct stateSpaceInformation.
53  * \return The Geometric Path equivalent of the trajectory.
54  */
55  ompl::geometric::PathGeometric toOMPLPath(const ompl::geometric::SimpleSetupPtr &ss);
56 
57  /** \brief Sets the trajectory from an OMPL Path and a reference state.
58  * \param[in] reference_state A full state that contains the values for all the joints.
59  * \param[in] path The geometric OMPL path to convert.
60  */
61  void fromOMPLPath(const robot_state::RobotState &reference_state,
62  const ompl::geometric::PathGeometric &path);
63  };
64  } // namespace OMPL
65 } // namespace robowflex
66 
67 #endif
#define ROBOWFLEX_CLASS_FORWARD(C)
Macro that forward declares a class and defines two shared ptrs types:
Definition: class_forward.h:16
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,...
Definition: trajectory.h:43
Functions for loading and animating robots in Blender.
Main namespace. Contains all library classes and functions.
Definition: scene.cpp:25
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")