GAMS  1.4.0
gams::platforms::DebugPlatform Class Reference

A debug platform that prints detailed status information. More...

#include <DebugPlatform.h>

Inheritance diagram for gams::platforms::DebugPlatform:
gams::platforms::BasePlatform

Public Member Functions

 DebugPlatform (madara::knowledge::KnowledgeBase *knowledge, variables::Sensors *sensors, variables::Platforms *platforms, variables::Self *self, const std::string &executions_location=".executions")
 Constructor. More...
 
 ~DebugPlatform ()
 Destructor. More...
 
virtual int analyze (void) override
 Analyzes platform information. More...
 
virtual double get_accuracy () const override
 Get the location aproximation value of what is considered close enough. More...
 
virtual const pose::ReferenceFrameget_frame (void) const
 Method for returning the platform's current frame. More...
 
virtual std::string get_id () const override
 Gets the unique identifier of the platform. More...
 
madara::knowledge::KnowledgeBase * get_knowledge_base (void) const
 Gets the knowledge base. More...
 
pose::Position get_location () const
 Gets Location of platform, within its parent frame. More...
 
virtual double get_min_sensor_range () const
 Gets sensor radius. More...
 
virtual double get_move_speed () const override
 Get move speed. More...
 
virtual std::string get_name () const override
 Gets the name of the platform. More...
 
pose::Orientation get_orientation () const
 Gets Orientation of platform, within its parent frame. More...
 
variables::PlatformStatusget_platform_status (void)
 Gets platform status information. More...
 
const variables::PlatformStatusget_platform_status (void) const
 Gets platform status information(const version) More...
 
pose::Pose get_pose () const
 Gets Pose of platform, within its parent frame. More...
 
utility::Positionget_position ()
 Gets GPS position. More...
 
variables::Selfget_self (void) const
 Gets self-referencing variables. More...
 
virtual const variables::Sensorget_sensor (const std::string &name) const
 Gets a sensor. More...
 
virtual void get_sensor_names (variables::SensorNames &sensors) const
 Fills a list of sensor names with sensors available on the platform. More...
 
variables::Sensorsget_sensors (void) const
 Gets the available sensor information. More...
 
virtual int home (void) override
 Instructs the agent to return home. More...
 
virtual int land (void) override
 Instructs the platform to land. More...
 
int move (const pose::Position &position, const pose::PositionBounds &bounds) override
 Moves the platform to a position. More...
 
virtual int move (const pose::Position &target)
 Moves the platform to a location. More...
 
virtual int move (const pose::Position &target)
 Moves the platform to a location. More...
 
virtual int move (const pose::Position &target, const pose::PositionBounds &bounds)
 Moves the platform to a location. More...
 
int move (const pose::Position &target, double epsilon)
 Moves the platform to a location. More...
 
int move (const pose::Position &target, double epsilon)
 Moves the platform to a location. More...
 
void operator= (const DebugPlatform &rhs)
 Assignment operator. More...
 
virtual int orient (const pose::Orientation &target)
 Rotates the platform to match a given angle. More...
 
virtual int orient (const pose::Orientation &target, const pose::OrientationBounds &bounds)
 Rotates the platform to match a given angle. More...
 
int orient (const pose::Orientation &target, double epsilon)
 Rotates the platform to match a given angle. More...
 
virtual void pause_move (void)
 Pauses movement, keeps source and dest at current values. More...
 
virtual int pose (const pose::Pose &target)
 Moves the platform to a pose(location and orientation) More...
 
virtual int pose (const pose::Pose &target, const pose::PoseBounds &bounds)
 Moves the platform to a pose(location and orientation) More...
 
int pose (const pose::Pose &target, double loc_epsilon, double rot_epsilon=M_PI/16)
 Moves the platform to a pose(location and orientation) More...
 
virtual void resume_move (void)
 Resumes movement status flags. More...
 
virtual void resume_orientation (void)
 Resumes orientation status flags. More...
 
virtual int sense (void) override
 Polls the sensor environment for useful information. More...
 
void set_knowledge (madara::knowledge::KnowledgeBase *rhs)
 Sets the knowledge base to use for the platform. More...
 
virtual void set_move_speed (const double &speed) override
 Set move speed. More...
 
virtual void set_sensors (variables::Sensors *sensors)
 Sets the map of sensor names to sensor information. More...
 
virtual void stop_move (void)
 Stops movement, resetting source and dest to current location. More...
 
virtual void stop_orientation (void)
 Stops orientation, resetting source and dest angles to current angle. More...
 
virtual int takeoff (void) override
 Instructs the platform to take off. More...
 

Protected Attributes

madara::knowledge::containers::Integer executions_
 Used to keep track of executions. More...
 
madara::knowledge::KnowledgeBase * knowledge_
 provides access to variables and values More...
 
double move_speed_
 movement speed for platform in meters/second More...
 
pose::Position position_
 current position More...
 
variables::Selfself_
 provides access to self state More...
 
variables::Sensorssensors_
 provides access to a sensor More...
 
variables::PlatformStatus status_
 provides access to status information for this platform More...
 

Detailed Description

A debug platform that prints detailed status information.

Definition at line 75 of file DebugPlatform.h.

Constructor & Destructor Documentation

◆ DebugPlatform()

gams::platforms::DebugPlatform::DebugPlatform ( madara::knowledge::KnowledgeBase *  knowledge,
variables::Sensors sensors,
variables::Platforms platforms,
variables::Self self,
const std::string &  executions_location = ".executions" 
)

Constructor.

Parameters
knowledgeknowledge base
sensorsmap of sensor names to sensor information
platformsmap of platform names to platform information
selfagent variables that describe self state
executions_locationlocation of an executions variable within the knowledge base to use for printing, after the .id identifier.

◆ ~DebugPlatform()

gams::platforms::DebugPlatform::~DebugPlatform ( )

Destructor.

Member Function Documentation

◆ analyze()

virtual int gams::platforms::DebugPlatform::analyze ( void  )
overridevirtual

Analyzes platform information.

Returns
bitmask status of the platform.
See also
Status.

Implements gams::platforms::BasePlatform.

◆ get_accuracy()

virtual double gams::platforms::DebugPlatform::get_accuracy ( ) const
overridevirtual

Get the location aproximation value of what is considered close enough.

Returns
location approximation radius

Reimplemented from gams::platforms::BasePlatform.

◆ get_frame()

virtual const pose::ReferenceFrame& gams::platforms::BasePlatform::get_frame ( void  ) const
virtualinherited

Method for returning the platform's current frame.

By default, returns pose::default_frame()

Returns
frame that the platform's coordinate system is operating in

◆ get_id()

virtual std::string gams::platforms::DebugPlatform::get_id ( ) const
overridevirtual

Gets the unique identifier of the platform.

This should be an alphanumeric identifier that can be used as part of a MADARA variable(e.g. vrep_ant, autonomous_snake, etc.)

Implements gams::platforms::BasePlatform.

◆ get_knowledge_base()

madara::knowledge::KnowledgeBase* gams::platforms::BasePlatform::get_knowledge_base ( void  ) const
inherited

Gets the knowledge base.

Returns
the knowledge base referenced by the algorithm and platform

◆ get_location()

pose::Position gams::platforms::BasePlatform::get_location ( ) const
inherited

Gets Location of platform, within its parent frame.

Returns
Location of platform

◆ get_min_sensor_range()

virtual double gams::platforms::BasePlatform::get_min_sensor_range ( ) const
virtualinherited

Gets sensor radius.

Returns
minimum radius of all available sensors for this platform

◆ get_move_speed()

virtual double gams::platforms::DebugPlatform::get_move_speed ( ) const
overridevirtual

Get move speed.

Reimplemented from gams::platforms::BasePlatform.

◆ get_name()

virtual std::string gams::platforms::DebugPlatform::get_name ( ) const
overridevirtual

Gets the name of the platform.

Implements gams::platforms::BasePlatform.

◆ get_orientation()

pose::Orientation gams::platforms::BasePlatform::get_orientation ( ) const
inherited

Gets Orientation of platform, within its parent frame.

Returns
Location of platform

◆ get_platform_status() [1/2]

variables::PlatformStatus* gams::platforms::BasePlatform::get_platform_status ( void  )
inherited

Gets platform status information.

Returns
platform status info

◆ get_platform_status() [2/2]

const variables::PlatformStatus* gams::platforms::BasePlatform::get_platform_status ( void  ) const
inherited

Gets platform status information(const version)

Returns
platform status info

◆ get_pose()

pose::Pose gams::platforms::BasePlatform::get_pose ( ) const
inherited

Gets Pose of platform, within its parent frame.

Returns
Location of platform

◆ get_position()

utility::Position* gams::platforms::BasePlatform::get_position ( )
inherited

Gets GPS position.

Returns
GPS location of platform

◆ get_self()

variables::Self* gams::platforms::BasePlatform::get_self ( void  ) const
inherited

Gets self-referencing variables.

Returns
self-referencing information like id and agent attributes

◆ get_sensor()

virtual const variables::Sensor& gams::platforms::BasePlatform::get_sensor ( const std::string &  name) const
virtualinherited

Gets a sensor.

Parameters
nameidentifier of sensor to get
Returns
Sensor object

◆ get_sensor_names()

virtual void gams::platforms::BasePlatform::get_sensor_names ( variables::SensorNames sensors) const
virtualinherited

Fills a list of sensor names with sensors available on the platform.

Parameters
sensorslist of sensors to fill

◆ get_sensors()

variables::Sensors* gams::platforms::BasePlatform::get_sensors ( void  ) const
inherited

Gets the available sensor information.

Returns
sensor information

◆ home()

virtual int gams::platforms::DebugPlatform::home ( void  )
overridevirtual

Instructs the agent to return home.

Returns
1 if moving, 2 if arrived, 0 if error

Reimplemented from gams::platforms::BasePlatform.

◆ land()

virtual int gams::platforms::DebugPlatform::land ( void  )
overridevirtual

Instructs the platform to land.

Returns
1 if moving, 2 if arrived, 0 if error

Reimplemented from gams::platforms::BasePlatform.

◆ move() [1/6]

int gams::platforms::DebugPlatform::move ( const pose::Position position,
const pose::PositionBounds bounds 
)
overridevirtual

Moves the platform to a position.

Parameters
positionthe coordinate to move to
epsilonapproximation value
Returns
1 if moving, 2 if arrived, 0 if error

Reimplemented from gams::platforms::BasePlatform.

◆ move() [2/6]

virtual int gams::platforms::BasePlatform::move ( const pose::Position target)
inlinevirtualinherited

Moves the platform to a location.

Parameters
locationthe coordinates to move to
Returns
the status of the move operation,
See also
PlatformReturnValues

Definition at line 230 of file BasePlatform.h.

◆ move() [3/6]

virtual int gams::platforms::BasePlatform::move
inline

Moves the platform to a location.

Parameters
locationthe coordinates to move to
Returns
the status of the move operation,
See also
PlatformReturnValues

Definition at line 230 of file BasePlatform.h.

◆ move() [4/6]

virtual int gams::platforms::BasePlatform::move

Moves the platform to a location.

Parameters
locationthe coordinates to move to
boundsobject to compute if platform has arrived
Returns
the status of the move operation,
See also
PlatformReturnValues

◆ move() [5/6]

int gams::platforms::BasePlatform::move ( const pose::Position target,
double  epsilon 
)
inlineinherited

Moves the platform to a location.

Parameters
locationthe coordinates to move to
epsilonapproximation value
Returns
the status of the move operation,
See also
PlatformReturnValues

Definition at line 249 of file BasePlatform.h.

◆ move() [6/6]

int gams::platforms::BasePlatform::move
inline

Moves the platform to a location.

Parameters
locationthe coordinates to move to
epsilonapproximation value
Returns
the status of the move operation,
See also
PlatformReturnValues

Definition at line 249 of file BasePlatform.h.

◆ operator=()

void gams::platforms::DebugPlatform::operator= ( const DebugPlatform rhs)

Assignment operator.

Parameters
rhsvalues to copy

◆ orient() [1/3]

virtual int gams::platforms::BasePlatform::orient ( const pose::Orientation target)
inlinevirtualinherited

Rotates the platform to match a given angle.

Parameters
targetthe orientation to move to
Returns
the status of the orient,
See also
PlatformReturnValues

Definition at line 258 of file BasePlatform.h.

◆ orient() [2/3]

virtual int gams::platforms::BasePlatform::orient ( const pose::Orientation target,
const pose::OrientationBounds bounds 
)
virtualinherited

Rotates the platform to match a given angle.

Parameters
targetthe orientation to move to
boundsobject to compute if platform has arrived
Returns
the status of the orient,
See also
PlatformReturnValues

Reimplemented in gams::platforms::JavaPlatform.

◆ orient() [3/3]

int gams::platforms::BasePlatform::orient ( const pose::Orientation target,
double  epsilon 
)
inlineinherited

Rotates the platform to match a given angle.

Parameters
targetthe orientation to move to
epsilonapproximation value
Returns
the status of the orient,
See also
PlatformReturnValues

Definition at line 277 of file BasePlatform.h.

◆ pause_move()

virtual void gams::platforms::BasePlatform::pause_move ( void  )
virtualinherited

Pauses movement, keeps source and dest at current values.

◆ pose() [1/3]

virtual int gams::platforms::BasePlatform::pose ( const pose::Pose target)
inlinevirtualinherited

Moves the platform to a pose(location and orientation)

This default implementation calls move and orient with the Location and Orientation portions of the target Pose. The return value is composed as follows: if either call returns ERROR(0), this call also returns ERROR(0). Otherwise, if BOTH calls return ARRIVED(2), this call also returns ARRIVED(2). Otherwise, this call returns MOVING(1)

Overrides might function differently.

Parameters
targetthe coordinates to move to
Returns
the status of the operation,
See also
PlatformReturnValues

Definition at line 296 of file BasePlatform.h.

◆ pose() [2/3]

virtual int gams::platforms::BasePlatform::pose ( const pose::Pose target,
const pose::PoseBounds bounds 
)
virtualinherited

Moves the platform to a pose(location and orientation)

This default implementation calls move and orient with the Location and Orientation portions of the target Pose. The return value is composed as follows: if either call returns ERROR(0), this call also returns ERROR(0). Otherwise, if BOTH calls return ARRIVED(2), this call also returns ARRIVED(2). Otherwise, this call returns MOVING(1)

Overrides might function differently.

Parameters
targetthe coordinates to move to
boundsobject to compute if platform has arrived
Returns
the status of the operation,
See also
PlatformReturnValues

◆ pose() [3/3]

int gams::platforms::BasePlatform::pose ( const pose::Pose target,
double  loc_epsilon,
double  rot_epsilon = M_PI/16 
)
inlineinherited

Moves the platform to a pose(location and orientation)

This default implementation calls move and orient with the Location and Orientation portions of the target Pose. The return value is composed as follows: if either call returns ERROR(0), this call also returns ERROR(0). Otherwise, if BOTH calls return ARRIVED(2), this call also returns ARRIVED(2). Otherwise, this call returns MOVING(1)

Overrides might function differently.

Parameters
targetthe coordinates to move to
loc_epsilonapproximation value for the location
rot_epsilonapproximation value for the orientation
Returns
the status of the operation,
See also
PlatformReturnValues

Definition at line 335 of file BasePlatform.h.

◆ resume_move()

virtual void gams::platforms::BasePlatform::resume_move ( void  )
virtualinherited

Resumes movement status flags.

◆ resume_orientation()

virtual void gams::platforms::BasePlatform::resume_orientation ( void  )
virtualinherited

Resumes orientation status flags.

◆ sense()

virtual int gams::platforms::DebugPlatform::sense ( void  )
overridevirtual

Polls the sensor environment for useful information.

Returns
number of sensors updated/used

Implements gams::platforms::BasePlatform.

◆ set_knowledge()

void gams::platforms::BasePlatform::set_knowledge ( madara::knowledge::KnowledgeBase *  rhs)
inherited

Sets the knowledge base to use for the platform.

Parameters
rhsthe new knowledge base to use

◆ set_move_speed()

virtual void gams::platforms::DebugPlatform::set_move_speed ( const double &  speed)
overridevirtual

Set move speed.

Parameters
speednew speed in meters/loop execution

Reimplemented from gams::platforms::BasePlatform.

◆ set_sensors()

virtual void gams::platforms::BasePlatform::set_sensors ( variables::Sensors sensors)
virtualinherited

Sets the map of sensor names to sensor information.

Parameters
sensorsmap of sensor names to sensor information

◆ stop_move()

virtual void gams::platforms::BasePlatform::stop_move ( void  )
virtualinherited

Stops movement, resetting source and dest to current location.

◆ stop_orientation()

virtual void gams::platforms::BasePlatform::stop_orientation ( void  )
virtualinherited

Stops orientation, resetting source and dest angles to current angle.

◆ takeoff()

virtual int gams::platforms::DebugPlatform::takeoff ( void  )
overridevirtual

Instructs the platform to take off.

Returns
1 if moving, 2 if arrived, 0 if error

Reimplemented from gams::platforms::BasePlatform.

Member Data Documentation

◆ executions_

madara::knowledge::containers::Integer gams::platforms::DebugPlatform::executions_
protected

Used to keep track of executions.

By default, this is setup to refer to the algorithm executions used in DebugAlgorithm(located at .executions in the knowledge base), but this can be changed to an arbitrary location in the constructor

Definition at line 188 of file DebugPlatform.h.

◆ knowledge_

madara::knowledge::KnowledgeBase* gams::platforms::BasePlatform::knowledge_
protectedinherited

provides access to variables and values

Definition at line 439 of file BasePlatform.h.

◆ move_speed_

double gams::platforms::BasePlatform::move_speed_
protectedinherited

movement speed for platform in meters/second

Definition at line 436 of file BasePlatform.h.

◆ position_

pose::Position gams::platforms::DebugPlatform::position_
protected

current position

Definition at line 179 of file DebugPlatform.h.

◆ self_

variables::Self* gams::platforms::BasePlatform::self_
protectedinherited

provides access to self state

Definition at line 442 of file BasePlatform.h.

◆ sensors_

variables::Sensors* gams::platforms::BasePlatform::sensors_
protectedinherited

provides access to a sensor

Definition at line 445 of file BasePlatform.h.

◆ status_

variables::PlatformStatus gams::platforms::BasePlatform::status_
protectedinherited

provides access to status information for this platform

Definition at line 448 of file BasePlatform.h.


The documentation for this class was generated from the following file: