GAMS  1.4.0
OscPlatform.h
Go to the documentation of this file.
1 
2 #ifndef _GAMS_PLATFORM_OSCPLATFORM_H_
3 #define _GAMS_PLATFORM_OSCPLATFORM_H_
4 
5 #ifdef _GAMS_OSC_
6 
7 #include <vector>
8 
9 #include "madara/knowledge/KnowledgeBase.h"
10 #include "madara/utility/EpochEnforcer.h"
11 #include "madara/utility/Timer.h"
12 
13 #include "gams/variables/Self.h"
14 #include "gams/variables/Sensor.h"
19 
20 #include "gams/utility/OscUdp.h"
21 
22 namespace gams { namespace platforms
23 {
28  class GAMS_EXPORT OscPlatform : public BasePlatform
29  {
30  public:
31 
32  enum MovementTypes
33  {
34  MOVEMENT_STOP_ON_ARRIVAL = 0,
35  MOVEMENT_PASSTHROUGH = 1
36  };
37 
44  OscPlatform(
45  madara::knowledge::KnowledgeBase * knowledge = 0,
46  gams::variables::Sensors * sensors = 0,
47  gams::variables::Self * self = 0,
48  const std::string & type = "quadcopter");
49 
53  virtual ~OscPlatform();
54 
59  virtual int sense(void) override;
60 
65  virtual int analyze(void) override;
66 
70  virtual std::string get_name() const override;
71 
78  virtual std::string get_id() const override;
79 
84  virtual double get_accuracy(void) const override;
85 
90  virtual double get_min_sensor_range(void) const override;
91 
96  virtual double get_move_speed(void) const override;
97 
102  virtual int home(void) override;
103 
108  virtual int land(void) override;
109 
116  int move(const pose::Position & location,
117  const pose::PositionBounds &bounds) override;
118 
119  using BasePlatform::move;
120 
127  int orient(const pose::Orientation & location,
128  const pose::OrientationBounds &bounds) override;
129 
130  using BasePlatform::orient;
131 
135  virtual void pause_move(void) override;
136 
141  virtual void set_move_speed(const double& speed) override;
142 
147  virtual void stop_move(void) override;
148 
153  virtual int takeoff(void) override;
154 
158  virtual const gams::pose::ReferenceFrame & get_frame(void) const override;
159 
160  private:
164  void build_prefixes(void);
165 
174  std::vector<double> calculate_thrust(
175  const pose::Position & current, const pose::Position & target,
176  bool & finished);
177 
179  gams::utility::OscUdp osc_;
180 
182  madara::transport::QoSTransportSettings settings_;
183 
185  std::string xy_velocity_prefix_;
186 
188  std::string z_velocity_prefix_;
189 
191  std::string yaw_velocity_prefix_;
192 
194  std::string position_prefix_;
195 
197  std::string rotation_prefix_;
198 
200  bool is_created_ = false;
201 
203  std::string json_creation_;
204 
206  pose::Position last_move_;
207 
209  pose::Orientation last_orient_;
210 
212  madara::utility::Timer<madara::utility::Clock> move_timer_;
213 
215  madara::utility::Timer<madara::utility::Clock> last_thrust_timer_;
216 
218  madara::utility::Timer<madara::utility::Clock> last_position_timer_;
219 
221  std::string type_;
222 
224  double loiter_timeout_;
225 
227  double respawn_timeout_;
228  }; // end OscPlatform class
229 
230 
234  class GAMS_EXPORT OscPlatformFactory : public PlatformFactory
235  {
236  public:
237 
243  OscPlatformFactory(const std::string & type = "quadcopter");
244 
248  virtual ~OscPlatformFactory();
249 
264  virtual BasePlatform * create(
265  const madara::knowledge::KnowledgeMap & args,
266  madara::knowledge::KnowledgeBase * knowledge,
267  variables::Sensors * sensors,
268  variables::Platforms * platforms,
269  variables::Self * self);
270 
272  std::string type_;
273  };
274 
275 } // end platforms namespace
276 } // end gams namespace
277 
278 #endif // #ifdef _GAMS_OSC_
279 
280 #endif // _GAMS_PLATFORM_OSCPLATFORM_H_
Copyright(c) 2014 Carnegie Mellon University.
#define GAMS_EXPORT
Definition: GamsExport.h:20
Copyright (c) 2019 James Edmondson.
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 orient(const pose::Orientation &target)
Rotates the platform to match a given angle.
Definition: BasePlatform.h:258
virtual int move(const pose::Position &target)
Moves the platform to a location.
Definition: BasePlatform.h:230
Provides Reference Frame (i.e., coordinate systemm) transforms.
A container for self referencing information.
Definition: Self.h:70
gams::pose::Orientation Orientation
Represents a orientation or orientation within a reference frame.
Definition: Orientation.h:94
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) 2015 Carnegie Mellon University.