Robowflex  v0.1
Making MoveIt Easy
fetch.h
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
3 #ifndef ROBOWFLEX_FETCH_
4 #define ROBOWFLEX_FETCH_
5 
8 
9 namespace robowflex
10 {
11  /** \cond IGNORE */
12  ROBOWFLEX_CLASS_FORWARD(FetchRobot);
13  /* \endcond */
14 
15  /** \class robowflex::FetchRobotPtr
16  \brief A shared pointer wrapper for robowflex::FetchRobot. */
17 
18  /** \class robowflex::FetchRobotConstPtr
19  \brief A const shared pointer wrapper for robowflex::FetchRobot. */
20 
21  /** \brief Convenience class that describes the default setup for Fetch.
22  * Will first attempt to load configuration and description from the robowflex_resources package.
23  * See https://github.com/KavrakiLab/robowflex_resources for this package.
24  * If this package is not available, then fetch_description / fetch_moveit_config packages will be used.
25  */
26  class FetchRobot : public Robot
27  {
28  public:
29  /** \brief Constructor.
30  */
31  FetchRobot();
32 
33  /** \brief Initialize the robot with arm and arm_with_torso kinematics.
34  * \param[in] addVirtual flag to add virtual joint.
35  * \param[in] use_low_limits flag to use lower joint limits.
36  * \return True on success, false on failure.
37  */
38  bool initialize(bool addVirtual = true, bool use_low_limits = false);
39 
40  /** \brief Inserts the caster links if they don't exist.
41  * \param[in] doc urdf description to be processed.
42  * \return True on success.
43  */
44  bool addCastersURDF(tinyxml2::XMLDocument &doc);
45 
46  /** \brief Sets the base pose of the Fetch robot (a virtual planar joint)
47  * \param[in] x The x position.
48  * \param[in] y The y position.
49  * \param[in] theta The angle.
50  */
51  void setBasePose(double x, double y, double theta);
52 
53  /** \brief Points the Fetch's head to a point in the world frame.
54  * \param[in] point The point to look at.
55  */
56  void pointHead(const Eigen::Vector3d &point);
57 
58  /** \brief Opens the Fetch's gripper.
59  */
60  void openGripper();
61 
62  /** \brief Closes the Fetch's gripper.
63  */
64  void closeGripper();
65 
66  private:
67  static const std::string DEFAULT_URDF; ///< Default URDF
68  static const std::string DEFAULT_SRDF; ///< Default SRDF
69  static const std::string DEFAULT_LIMITS; ///< Default Limits
70  static const std::string DEFAULT_KINEMATICS; ///< Default kinematics
71 
72  static const std::string RESOURCE_URDF; ///< URDF from robowflex_resources
73  static const std::string RESOURCE_SRDF; ///< SRDF from robowflex_resources
74  static const std::string RESOURCE_LIMITS; ///< Limits from robowflex_resources
75  static const std::string RESOURCE_LIMITS_LOW; ///< Lower limits from robowflex_resources
76  static const std::string RESOURCE_KINEMATICS; ///< kinematics from robowflex_resources
77  };
78 
79  namespace OMPL
80  {
81  /** \cond IGNORE */
82  ROBOWFLEX_CLASS_FORWARD(FetchOMPLPipelinePlanner);
83  /* \endcond */
84 
85  /** \class robowflex::OMPL::FetchOMPLPipelinePlannerPtr
86  \brief A shared pointer wrapper for robowflex::OMPL::FetchOMPLPipelinePlanner. */
87 
88  /** \class robowflex::OMPL::FetchOMPLPipelinePlannerConstPtr
89  \brief A const shared pointer wrapper for robowflex::OMPL::FetchOMPLPipelinePlanner. */
90 
91  /** \brief Convenience class for the default motion planning pipeline for Fetch.
92  */
94  {
95  public:
96  /** \brief Constructor.
97  * \param[in] robot Robot to create planner for.
98  * \param[in] name Namespace of this planner.
99  */
100  FetchOMPLPipelinePlanner(const RobotPtr &robot, const std::string &name = "");
101 
102  /** \brief Initialize the planning context. All parameter provided are defaults.
103  * \param[in] settings Settings to set on the parameter server.
104  * \param[in] adapters Planning adapters to load.
105  * \return True on success, false on failure.
106  */
107  bool initialize(const Settings &settings = Settings(),
108  const std::vector<std::string> &adapters = DEFAULT_ADAPTERS);
109 
110  private:
111  static const std::string DEFAULT_CONFIG; ///< Default planning configuration.
112  static const std::string RESOURCE_CONFIG; ///< Planning configuration from robowflex_resources.
113  };
114  } // namespace OMPL
115 } // namespace robowflex
116 
117 #endif
#define ROBOWFLEX_CLASS_FORWARD(C)
Macro that forward declares a class and defines two shared ptrs types:
Definition: class_forward.h:16
Convenience class that describes the default setup for Fetch. Will first attempt to load configuratio...
Definition: fetch.h:27
static const std::string RESOURCE_SRDF
SRDF from robowflex_resources.
Definition: fetch.h:73
static const std::string DEFAULT_URDF
Default URDF.
Definition: fetch.h:67
static const std::string DEFAULT_SRDF
Default SRDF.
Definition: fetch.h:68
FetchRobot()
Constructor.
Definition: fetch.cpp:29
void openGripper()
Opens the Fetch's gripper.
Definition: fetch.cpp:111
static const std::string RESOURCE_KINEMATICS
kinematics from robowflex_resources
Definition: fetch.h:76
static const std::string RESOURCE_URDF
URDF from robowflex_resources.
Definition: fetch.h:72
static const std::string RESOURCE_LIMITS_LOW
Lower limits from robowflex_resources.
Definition: fetch.h:75
static const std::string RESOURCE_LIMITS
Limits from robowflex_resources.
Definition: fetch.h:74
bool initialize(bool addVirtual=true, bool use_low_limits=false)
Initialize the robot with arm and arm_with_torso kinematics.
Definition: fetch.cpp:33
void closeGripper()
Closes the Fetch's gripper.
Definition: fetch.cpp:119
static const std::string DEFAULT_KINEMATICS
Default kinematics.
Definition: fetch.h:70
void setBasePose(double x, double y, double theta)
Sets the base pose of the Fetch robot (a virtual planar joint)
Definition: fetch.cpp:127
bool addCastersURDF(tinyxml2::XMLDocument &doc)
Inserts the caster links if they don't exist.
Definition: fetch.cpp:65
void pointHead(const Eigen::Vector3d &point)
Points the Fetch's head to a point in the world frame.
Definition: fetch.cpp:96
static const std::string DEFAULT_LIMITS
Default Limits.
Definition: fetch.h:69
Convenience class for the default motion planning pipeline for Fetch.
Definition: fetch.h:94
static const std::string RESOURCE_CONFIG
Planning configuration from robowflex_resources.
Definition: fetch.h:112
bool initialize(const Settings &settings=Settings(), const std::vector< std::string > &adapters=DEFAULT_ADAPTERS)
Initialize the planning context. All parameter provided are defaults.
Definition: fetch.cpp:146
static const std::string DEFAULT_CONFIG
Default planning configuration.
Definition: fetch.h:111
FetchOMPLPipelinePlanner(const RobotPtr &robot, const std::string &name="")
Constructor.
Definition: fetch.cpp:141
A robowflex::PipelinePlanner that uses the MoveIt! default OMPL planning pipeline.
static const std::vector< std::string > DEFAULT_ADAPTERS
The default planning adapters.
Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline.
A shared pointer wrapper for robowflex::Robot.
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