grvc_ual  2.2
An abstraction layer for unmanned aerial vehicles
Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
grvc::ual::Backend Class Referenceabstract

Common interface for back-end implementations of ual. More...

#include <backend.h>

Inheritance diagram for grvc::ual::Backend:
Inheritance graph
[legend]

Public Types

enum  State {
  UNINITIALIZED, LANDED_DISARMED, LANDED_ARMED, TAKING_OFF,
  FLYING_AUTO, FLYING_MANUAL, LANDING
}
 Possible backend states.
 

Public Member Functions

template<typename Callable , typename... Args>
bool threadSafeCall (Callable &&_fn, Args &&..._args)
 Wrap a Backend function to make it thread-safe.
 
 Backend ()
 Constructor inits node.
 
virtual bool isReady () const =0
 Backend is initialized and ready to run tasks?
 
bool isIdle ()
 Is it idle?
 
virtual Pose pose ()=0
 Latest pose estimation of the robot.
 
virtual Velocity velocity () const =0
 Latest velocity estimation of the robot.
 
virtual Odometry odometry () const =0
 Latest odometry estimation of the robot.
 
virtual Transform transform () const =0
 Latest transform estimation of the robot.
 
State state ()
 Current robot state.
 
virtual void setPose (const geometry_msgs::PoseStamped &_pose)=0
 
virtual void goToWaypoint (const Waypoint &_wp)=0
 
virtual void goToWaypointGeo (const WaypointGeo &_wp)=0
 
virtual void takeOff (double _height)=0
 Follow a list of waypoints, one after another. More...
 
virtual void land ()=0
 Land on the current position.
 
virtual void setVelocity (const Velocity &_vel)=0
 
virtual void recoverFromManual ()=0
 
virtual void setHome (bool set_z)=0
 Set home position.
 
void abort (bool _freeze=true)
 Cancel execution of the current task.
 

Static Public Member Functions

static BackendcreateBackend ()
 Create an adequate Backend depending on current platform and command arguments. More...
 

Protected Attributes

std::atomic< bool > abort_ = {false}
 
std::atomic< bool > freeze_ = {false}
 
std::mutex running_mutex_
 
std::atomic< bool > running_task_ = {false}
 
std::thread spin_thread_
 
std::atomic< Statestate_ = {UNINITIALIZED}
 

Detailed Description

Common interface for back-end implementations of ual.

Member Function Documentation

static Backend* grvc::ual::Backend::createBackend ( )
static

Create an adequate Backend depending on current platform and command arguments.

Parameters
_argcnumber of arguments in _argv
_argvcommand line arguments passed to the program. This arguments will be parsed and used to select the best fitting implementation of Backend from those available in the current platform.
Returns
the newly created Backend. Whoever calls this method, is responsible for eventually destroying the Backend.
virtual void grvc::ual::Backend::goToWaypoint ( const Waypoint &  _wp)
pure virtual

Go to the specified waypoint, following a straight line

Parameters
_wpgoal waypoint

Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.

virtual void grvc::ual::Backend::goToWaypointGeo ( const WaypointGeo &  _wp)
pure virtual

Go to the specified waypoint in geographic coordinates, following a straight line

Parameters
_wpgoal waypoint in geographic coordinates

Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.

virtual void grvc::ual::Backend::recoverFromManual ( )
pure virtual

Recover from manual flight mode Use it when FLYING uav is switched to manual mode and want to go BACK to auto.

Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.

virtual void grvc::ual::Backend::setPose ( const geometry_msgs::PoseStamped &  _pose)
pure virtual

Set pose

Parameters
_posetarget pose

Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.

virtual void grvc::ual::Backend::setVelocity ( const Velocity &  _vel)
pure virtual

Set velocities

Parameters
_veltarget velocity in world coordinates

Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.

virtual void grvc::ual::Backend::takeOff ( double  _height)
pure virtual

Follow a list of waypoints, one after another.

Perform a take off maneuver

Parameters
_heighttarget height that must be reached to consider the take off complete

Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.

Member Data Documentation

std::atomic<bool> grvc::ual::Backend::abort_ = {false}
protected

Abort flag If you want your task to be abortable, check its value periodically

std::atomic<bool> grvc::ual::Backend::freeze_ = {false}
protected

Freeze flag When aborting a task, freezes the platform if it is true

std::mutex grvc::ual::Backend::running_mutex_
protected

Simplest state-machine model: idle/running Implemented via mutex-locking


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