GAMS  1.4.0
BasePlatform.h
Go to the documentation of this file.
1 
54 #ifndef _GAMS_PLATFORM_BASE_H_
55 #define _GAMS_PLATFORM_BASE_H_
56 
57 #include <string>
58 
59 #include "gams/variables/Self.h"
60 #include "gams/variables/Sensor.h"
64 #include "gams/pose/Position.h"
65 #include "gams/pose/Pose.h"
66 #include "gams/pose/Epsilon.h"
67 #include "madara/knowledge/KnowledgeBase.h"
68 
69 namespace gams
70 {
71  namespace controllers
72  {
73  class BaseController;
74  class Multicontroller;
75  }
76 
77  namespace platforms
78  {
83  {
84  UNKNOWN = 0,
85  OK = 1,
86  WAITING = 2,
88  FAILED = 8,
89  MOVING = 16,
94  MOVEMENT_AVAILABLE = 2048
95  };
96 
101  {
106  PLATFORM_ARRIVED = 2
107  };
108 
113  {
114  public:
115  // allow Base controller to initialize our variables
118 
126  madara::knowledge::KnowledgeBase * knowledge = 0,
127  variables::Sensors * sensors = 0,
128  variables::Self * self = 0);
129 
133  virtual ~BasePlatform();
134 
139  void operator=(const BasePlatform & rhs);
140 
145  virtual int analyze(void) = 0;
146 
151  virtual double get_accuracy(void) const;
152 
158 
164 
170 
176 
180  virtual std::string get_name() const = 0;
181 
187  virtual std::string get_id() const = 0;
188 
193  virtual double get_min_sensor_range() const;
194 
198  virtual double get_move_speed() const;
199 
205  virtual const variables::Sensor & get_sensor(const std::string& name) const;
206 
211  virtual void get_sensor_names(variables::SensorNames & sensors) const;
212 
217  virtual int home(void);
218 
223  virtual int land(void);
224 
230  virtual int move(const pose::Position & target) {
231  return move(target, pose::Epsilon());
232  }
233 
240  virtual int move(const pose::Position & target,
241  const pose::PositionBounds &bounds);
242 
249  int move(const pose::Position & target, double epsilon) {
250  return move(target, pose::Epsilon(epsilon));
251  }
252 
258  virtual int orient(const pose::Orientation & target) {
259  return orient(target, pose::Epsilon());
260  }
261 
268  virtual int orient(const pose::Orientation & target,
269  const pose::OrientationBounds &bounds);
270 
277  int orient(const pose::Orientation & target, double epsilon) {
278  return orient(target, pose::Epsilon(epsilon));
279  }
280 
296  virtual int pose(const pose::Pose & target) {
297  return pose(target, pose::Epsilon());
298  }
299 
316  virtual int pose(const pose::Pose & target, const pose::PoseBounds &bounds);
317 
335  int pose(const pose::Pose & target,
336  double loc_epsilon, double rot_epsilon = M_PI/16) {
337  return pose(target, pose::Epsilon(loc_epsilon, rot_epsilon));
338  }
339 
343  virtual void pause_move(void);
344 
349  virtual int sense(void) = 0;
350 
355  void set_knowledge(madara::knowledge::KnowledgeBase * rhs);
356 
361  virtual void set_move_speed(const double& speed);
362 
367  virtual void set_sensors(variables::Sensors * sensors);
368 
372  virtual void stop_move(void);
373 
377  virtual void resume_move(void);
378 
382  virtual void resume_orientation(void);
383 
387  virtual void stop_orientation(void);
388 
393  virtual int takeoff(void);
394 
399  madara::knowledge::KnowledgeBase * get_knowledge_base(void) const;
400 
405  variables::Self * get_self(void) const;
406 
412 
418 
424 
432  virtual const pose::ReferenceFrame & get_frame(void) const;
433 
434  protected:
436  double move_speed_;
437 
439  madara::knowledge::KnowledgeBase * knowledge_;
440 
443 
446 
449 
451  //static pose::GPSFrame frame_;
452  };
453 
454  // deprecated typdef. Please use BasePlatform instead.
456  }
457 }
458 
459 #include "BasePlatform.inl"
460 
461 #endif // _GAMS_PLATFORM_BASE_H_
Copyright (c) 2019 Carnegie Mellon University.
Copyright (c) 2014 Carnegie Mellon University.
#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.
The basic controller that can be used to perform actions on platforms and algorithms.
A controller that has the capability of managing multiple controllers.
The base platform for all platforms to use.
Definition: BasePlatform.h:113
virtual double get_move_speed() const
Gets move speed.
utility::Position * get_position()
Gets GPS position.
madara::knowledge::KnowledgeBase * knowledge_
provides access to variables and values
Definition: BasePlatform.h:439
double move_speed_
movement speed for platform in meters/second
Definition: BasePlatform.h:436
virtual int takeoff(void)
Instructs the agent to take off.
int move(const pose::Position &target, double epsilon)
Moves the platform to a location.
Definition: BasePlatform.h:249
BasePlatform(madara::knowledge::KnowledgeBase *knowledge=0, variables::Sensors *sensors=0, variables::Self *self=0)
Constructor.
virtual int orient(const pose::Orientation &target, const pose::OrientationBounds &bounds)
Rotates the platform to match a given angle.
virtual int move(const pose::Position &target, const pose::PositionBounds &bounds)
Moves the platform to a location.
virtual std::string get_id() const =0
Gets the unique identifier of the platform.
variables::PlatformStatus status_
provides access to status information for this platform
Definition: BasePlatform.h:448
virtual const pose::ReferenceFrame & get_frame(void) const
Method for returning the platform's current frame.
virtual ~BasePlatform()
Destructor.
virtual void resume_orientation(void)
Resumes orientation status flags.
virtual void stop_orientation(void)
Stops orientation, resetting source and dest angles to current angle.
pose::Pose get_pose() const
Gets Pose of platform, within its parent frame.
int orient(const pose::Orientation &target, double epsilon)
Rotates the platform to match a given angle.
Definition: BasePlatform.h:277
variables::Self * self_
provides access to self state
Definition: BasePlatform.h:442
virtual const variables::Sensor & get_sensor(const std::string &name) const
Gets a sensor.
virtual int orient(const pose::Orientation &target)
Rotates the platform to match a given angle.
Definition: BasePlatform.h:258
virtual void resume_move(void)
Resumes movement status flags.
variables::Self * get_self(void) const
Gets self-referencing variables.
const variables::PlatformStatus * get_platform_status(void) const
Gets platform status information(const version)
virtual std::string get_name() const =0
Gets the name of the platform.
virtual int pose(const pose::Pose &target, const pose::PoseBounds &bounds)
Moves the platform to a pose(location and orientation)
void operator=(const BasePlatform &rhs)
Assignment operator.
virtual double get_accuracy(void) const
Gets the position accuracy in meters.
variables::PlatformStatus * get_platform_status(void)
Gets platform status information.
variables::Sensors * get_sensors(void) const
Gets the available sensor information.
int pose(const pose::Pose &target, double loc_epsilon, double rot_epsilon=M_PI/16)
Moves the platform to a pose(location and orientation)
Definition: BasePlatform.h:335
virtual int move(const pose::Position &target)
Moves the platform to a location.
Definition: BasePlatform.h:230
virtual int land(void)
Instructs the agent to land.
virtual int home(void)
Instructs the agent to return home.
virtual void set_sensors(variables::Sensors *sensors)
Sets the map of sensor names to sensor information.
virtual void set_move_speed(const double &speed)
Set move speed.
pose::Position get_location() const
Gets Location of platform, within its parent frame.
virtual void stop_move(void)
Stops movement, resetting source and dest to current location.
virtual int sense(void)=0
Polls the sensor environment for useful information.
madara::knowledge::KnowledgeBase * get_knowledge_base(void) const
Gets the knowledge base.
virtual void get_sensor_names(variables::SensorNames &sensors) const
Fills a list of sensor names with sensors available on the platform.
virtual double get_min_sensor_range() const
Gets sensor radius.
variables::Sensors * sensors_
provides access to a sensor
Definition: BasePlatform.h:445
virtual void pause_move(void)
Pauses movement, keeps source and dest at current values.
pose::Orientation get_orientation() const
Gets Orientation of platform, within its parent frame.
virtual int pose(const pose::Pose &target)
Moves the platform to a pose(location and orientation)
Definition: BasePlatform.h:296
void set_knowledge(madara::knowledge::KnowledgeBase *rhs)
Sets the knowledge base to use for the platform.
virtual int analyze(void)=0
Analyzes platform information.
A simple bounds checker which tests whether the current position is within the given number of meters...
Definition: Epsilon.h:101
Interface for defining a bounds checker for Orientations.
Definition: Epsilon.h:80
Interface for defining a bounds checker for Poses, a combination of position and orientation checking...
Definition: Epsilon.h:94
Interface for defining a bounds checker for Positions.
Definition: Epsilon.h:68
Provides Reference Frame (i.e., coordinate systemm) transforms.
A position in an x, y, z coordinate system.
Definition: Position.h:78
A container for platform status information.
A container for self referencing information.
Definition: Self.h:70
A container for sensor information.
Definition: Sensor.h:81
PlatformAnalyzeStatus
Possible platform statuses, as returnable by analyze()
Definition: BasePlatform.h:83
@ REDUCED_MOVEMENT_AVAILABLE
Definition: BasePlatform.h:91
PlatformReturnValues
Platform return values.
Definition: BasePlatform.h:101
BasePlatform Base
Definition: BasePlatform.h:455
std::vector< std::string > SensorNames
a list of sensor names
Definition: Sensor.h:241
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.
Copyright (c) 2015-2018 Carnegie Mellon University.
Copyright (c) 2015 Carnegie Mellon University.