GAMS  1.4.0
RosP3Dx.h
Go to the documentation of this file.
1 
54 #ifndef _GAMS_PLATFORM_RosP3Dx_H_
55 #define _GAMS_PLATFORM_RosP3Dx_H_
56 
57 #ifdef _GAMS_ROS_
58 
60 
61 #include "gams/variables/Self.h"
62 #include "gams/variables/Sensor.h"
64 #include "gams/utility/Position.h"
66 #include "madara/knowledge/KnowledgeBase.h"
67 
68 // ROS includes
69 #ifdef __GNUC__
70 #pragma GCC diagnostic push
71 #pragma GCC diagnostic ignored "-Wpedantic"
72 #endif
73 
74 #include "ros/ros.h"
75 #include "move_base_msgs/MoveBaseAction.h"
76 #include "actionlib/client/simple_action_client.h"
77 #include "geometry_msgs/PoseWithCovarianceStamped.h"
78 
79 #ifdef __GNUC__
80 #pragma GCC diagnostic pop
81 #endif
82 
83 namespace gams
84 {
85  namespace platforms
86  {
87  class GAMS_EXPORT RosP3Dx : public RosBase
88  {
89  public:
97  RosP3Dx (
98  madara::knowledge::KnowledgeBase * knowledge,
99  variables::Sensors * sensors,
100  variables::Platforms * platforms,
101  variables::Self * self);
102 
106  virtual ~RosP3Dx () override = default;
107 
113  virtual std::string get_id () const override;
114 
118  virtual std::string get_name () const override;
119 
126  int move (const pose::Position & position,
127  const pose::PositionBounds &bounds) override;
128 
129  // inherit BasePlatform's move overloads
130  using BasePlatform::move;
131 
132  protected:
133  const std::string ros_namespace_;
134  ros::NodeHandle node_handle_;
135  actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> move_client_;
136  ros::Subscriber amcl_pose_sub_;
137  ros::AsyncSpinner spinner_;
138  bool init_pose_set_;
139 
140  void set_initial_position(const pose::Position& p);
141 
142  void update_pose(const geometry_msgs::PoseWithCovarianceStamped& msg);
143  }; // class RosP3Dx
144 
148  class GAMS_EXPORT RosP3DxFactory : public PlatformFactory
149  {
150  public:
151 
164  virtual BasePlatform * create (
165  const madara::knowledge::KnowledgeMap & args,
166  madara::knowledge::KnowledgeBase * knowledge,
167  variables::Sensors * sensors,
168  variables::Platforms * platforms,
169  variables::Self * self);
170  }; // class RosP3DxFactory
171  } // namespace platform
172 } // namespace gams
173 
174 #endif // _GAMS_ROS_
175 
176 #endif // _GAMS_PLATFORM_RosP3Dx_H_
#define GAMS_EXPORT
Definition: GamsExport.h:20
Copyright(c) 2014 Carnegie Mellon University.
Copyright(c) 2014 Carnegie Mellon University.
Copyright (c) 2014 Carnegie Mellon University.
Copyright(c) 2014 Carnegie Mellon University.
Copyright(c) 2014 Carnegie Mellon University.
virtual int move(const pose::Position &target)
Moves the platform to a location.
Definition: BasePlatform.h:230
std::map< std::string, PlatformStatus > Platforms
a map of sensor names to the sensor information
std::map< std::string, Sensor * > Sensors
a map of sensor names to the sensor information
Definition: Sensor.h:238
Contains all GAMS-related tools, classes and code.
Copyright(c) 2014 Carnegie Mellon University.