GAMS  1.4.0
OscJoystickPlatform.h
Go to the documentation of this file.
1 
2 #ifndef _GAMS_PLATFORM_OSC_JOYSTICK_PLATFORM_H_
3 #define _GAMS_PLATFORM_OSC_JOYSTICK_PLATFORM_H_
4 
5 #ifdef _GAMS_OSC_
6 
7 #include <vector>
8 
9 #include "madara/knowledge/KnowledgeBase.h"
10 #include "madara/knowledge/containers/NativeDoubleVector.h"
11 #include "madara/utility/EpochEnforcer.h"
12 #include "madara/utility/Timer.h"
13 
14 #include "gams/variables/Self.h"
15 #include "gams/variables/Sensor.h"
20 
21 #include "gams/utility/OscUdp.h"
22 
23 namespace gams { namespace platforms
24 {
29  class GAMS_EXPORT OscJoystickPlatform : public BasePlatform
30  {
31  public:
32 
33  enum MovementTypes
34  {
35  MOVEMENT_STOP_ON_ARRIVAL = 0,
36  MOVEMENT_PASSTHROUGH = 1
37  };
38 
45  OscJoystickPlatform(
46  madara::knowledge::KnowledgeBase * knowledge = 0,
47  gams::variables::Sensors * sensors = 0,
48  gams::variables::Self * self = 0,
49  const std::string & type = "quadcopter");
50 
54  virtual ~OscJoystickPlatform();
55 
60  virtual int sense(void) override;
61 
66  virtual int analyze(void) override;
67 
71  virtual std::string get_name() const override;
72 
79  virtual std::string get_id() const override;
80 
85  virtual double get_accuracy(void) const override;
86 
91  virtual double get_min_sensor_range(void) const override;
92 
97  virtual double get_move_speed(void) const override;
98 
103  virtual int home(void) override;
104 
109  virtual int land(void) override;
110 
117  int move(const pose::Position & location,
118  const pose::PositionBounds &bounds) override;
119 
120  using BasePlatform::move;
121 
128  int orient(const pose::Orientation & location,
129  const pose::OrientationBounds &bounds) override;
130 
131  using BasePlatform::orient;
132 
136  virtual void pause_move(void) override;
137 
142  virtual void set_move_speed(const double& speed) override;
143 
148  virtual void stop_move(void) override;
149 
154  virtual int takeoff(void) override;
155 
159  virtual const gams::pose::ReferenceFrame & get_frame(void) const override;
160 
161  private:
165  void build_prefixes(void);
166 
175  std::vector<double> calculate_thrust(
176  const pose::Position & current, const pose::Position & target,
177  bool & finished);
178 
180  gams::utility::OscUdp osc_;
181 
183  madara::transport::QoSTransportSettings settings_;
184 
186  std::string xy_velocity_prefix_;
187 
189  std::string z_velocity_prefix_;
190 
192  std::string yaw_velocity_prefix_;
193 
195  std::string position_prefix_;
196 
198  std::string rotation_prefix_;
199 
201  bool is_created_ = false;
202 
204  std::string json_creation_;
205 
207  pose::Position last_move_;
208 
210  pose::Orientation last_orient_;
211 
213  madara::utility::Timer<madara::utility::Clock> move_timer_;
214 
216  madara::utility::Timer<madara::utility::Clock> last_thrust_timer_;
217 
219  madara::utility::Timer<madara::utility::Clock> last_position_timer_;
220 
222  std::string type_;
223 
225  double loiter_timeout_;
226 
228  std::string event_fd_;
229 
231  bool inverted_y_;
232 
234  bool inverted_z_;
235 
237  bool flip_xy_;
238 
240  madara::knowledge::containers::NativeDoubleVector xyz_velocity_;
241 
243  madara::threads::Threader threader_;
244 
245  }; // end OscJoystickPlatform class
246 
247 
251  class GAMS_EXPORT OscJoystickPlatformFactory : public PlatformFactory
252  {
253  public:
254 
260  OscJoystickPlatformFactory(const std::string & type = "quadcopter");
261 
265  virtual ~OscJoystickPlatformFactory();
266 
281  virtual BasePlatform * create(
282  const madara::knowledge::KnowledgeMap & args,
283  madara::knowledge::KnowledgeBase * knowledge,
284  variables::Sensors * sensors,
285  variables::Platforms * platforms,
286  variables::Self * self);
287 
289  std::string type_;
290  };
291 
292 } // end platforms namespace
293 } // end gams namespace
294 
295 #endif // #ifdef _GAMS_OSC_
296 
297 
298 #endif // _GAMS_PLATFORM_OSC_JOYSTICK_PLATFORM_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.