Robowflex  v0.1
Making MoveIt Easy
r2.h
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
3 #ifndef ROBOWFLEX_R2_
4 #define ROBOWFLEX_R2_
5 
8 
9 namespace robowflex
10 {
11  /** \cond IGNORE */
12  ROBOWFLEX_CLASS_FORWARD(R2Robot);
13  /* \endcond */
14 
15  /** \class robowflex::R2RobotPtr
16  \brief A shared pointer wrapper for robowflex::R2Robot. */
17 
18  /** \class robowflex::R2RobotConstPtr
19  \brief A const shared pointer wrapper for robowflex::R2Robot. */
20 
21  /** \brief Convenience class that describes the default setup for R2 (R2C6 full).
22  */
23  class R2Robot : public Robot
24  {
25  public:
26  /** \brief Constructor.
27  */
29 
30  /** \brief Initialize the robot with a few kinematics groups.
31  * \param[in] kinematics List of kinematics solvers for planning groups to load.
32  * \return True on success, false on failure.
33  */
35 
36  /** \brief Loads telemetry data from SMT from an HDF5 file into a robot trajectory.
37  * \param[in] filename Filename to load.
38  * \return A robot trajectory corresponding to the data.
39  */
40  robot_trajectory::RobotTrajectoryPtr loadSMTData(const std::string &filename);
41 
42  private:
43  static const std::string URDF; ///< Default URDF
44  static const std::string SRDF; ///< Default SRDF
45  static const std::string LIMITS; ///< Default Limits
46  static const std::string KINEMATICS; ///< Default kinematics
47  static const std::string CACHED; ///< IK Cache location
48  static const std::vector<std::string> SAMPLERS; ///< Constraint samplers
49  static const std::map<std::string, std::string> CREEPY; ///< Faster IK chains
50  };
51 
52  namespace OMPL
53  {
54  /** \cond IGNORE */
55  ROBOWFLEX_CLASS_FORWARD(R2OMPLPipelinePlanner);
56  /* \endcond */
57 
58  /** \class robowflex::OMPL::R2OMPLPipelinePlannerPtr
59  \brief A shared pointer wrapper for robowflex::OMPL::R2OMPLPipelinePlanner. */
60 
61  /** \class robowflex::OMPL::R2OMPLPipelinePlannerConstPtr
62  \brief A const shared pointer wrapper for robowflex::OMPL::R2OMPLPipelinePlanner. */
63 
64  /** \brief Convenience class for the default motion planning pipeline for R2 (R2C6 full).
65  */
67  {
68  public:
69  /** \brief Constructor.
70  * \param[in] robot Robot to create planner for.
71  * \param[in] name Namespace of this planner.
72  */
74 
75  /** \brief Initialize the planning context. All parameter provided are defaults.
76  * \param[in] config_file A YAML file containing OMPL planner configurations.
77  * \param[in] settings Settings to set on the parameter server.
78  * \param[in] plugin Planning plugin to load.
79  * \param[in] adapters Planning adapters to load.
80  * \return True on success, false on failure.
81  */
82  bool initialize(const std::string &config_file = CONFIG, const Settings &settings = Settings(),
83  const std::string &plugin = PLUGIN,
84  const std::vector<std::string> &adapters = DEFAULT_ADAPTERS);
85 
86  private:
87  static const std::string CONFIG; ///< Default planning configuration.
88  static const std::string PLUGIN; ///< Default planning plugin.
89  };
90  } // namespace OMPL
91 } // namespace robowflex
92 
93 #endif
#define ROBOWFLEX_CLASS_FORWARD(C)
Macro that forward declares a class and defines two shared ptrs types:
Definition: class_forward.h:16
A robowflex::PipelinePlanner that uses the MoveIt! default OMPL planning pipeline.
static const std::vector< std::string > DEFAULT_ADAPTERS
The default planning adapters.
Convenience class for the default motion planning pipeline for R2 (R2C6 full).
Definition: r2.h:67
static const std::string PLUGIN
Default planning plugin.
Definition: r2.h:88
bool initialize(const std::string &config_file=CONFIG, const Settings &settings=Settings(), const std::string &plugin=PLUGIN, const std::vector< std::string > &adapters=DEFAULT_ADAPTERS)
Initialize the planning context. All parameter provided are defaults.
R2OMPLPipelinePlanner(const R2RobotPtr &robot, const std::string &name="")
Constructor.
static const std::string CONFIG
Default planning configuration.
Definition: r2.h:87
Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline.
A shared pointer wrapper for robowflex::R2Robot.
Convenience class that describes the default setup for R2 (R2C6 full).
Definition: r2.h:24
static const std::string LIMITS
Default Limits.
Definition: r2.h:45
robot_trajectory::RobotTrajectoryPtr loadSMTData(const std::string &filename)
Loads telemetry data from SMT from an HDF5 file into a robot trajectory.
R2Robot()
Constructor.
static const std::map< std::string, std::string > CREEPY
Faster IK chains.
Definition: r2.h:49
static const std::string SRDF
Default SRDF.
Definition: r2.h:44
static const std::string CACHED
IK Cache location.
Definition: r2.h:47
static const std::vector< std::string > SAMPLERS
Constraint samplers.
Definition: r2.h:48
static const std::string URDF
Default URDF.
Definition: r2.h:43
static const std::string KINEMATICS
Default kinematics.
Definition: r2.h:46
bool initialize(const std::vector< std::string > kinematics)
Initialize the robot with a few kinematics groups.
Loads information about a robot and maintains information about a robot's state.
Functions for loading and animating robots in Blender.
Main namespace. Contains all library classes and functions.
Definition: scene.cpp:25