| 
    grvc_ual
    2.2
    
   An abstraction layer for unmanned aerial vehicles 
   | 
 
Common interface for back-end implementations of ual. More...
#include <backend.h>

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 Backend * | createBackend () | 
| 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< State > | state_ = {UNINITIALIZED} | 
Common interface for back-end implementations of ual.
      
  | 
  static | 
Create an adequate Backend depending on current platform and command arguments.
| _argc | number of arguments in _argv | 
| _argv | command 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. | 
      
  | 
  pure virtual | 
Go to the specified waypoint, following a straight line
| _wp | goal waypoint | 
Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.
      
  | 
  pure virtual | 
Go to the specified waypoint in geographic coordinates, following a straight line
| _wp | goal waypoint in geographic coordinates | 
Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.
      
  | 
  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.
      
  | 
  pure virtual | 
Set pose
| _pose | target pose | 
Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.
      
  | 
  pure virtual | 
Set velocities
| _vel | target velocity in world coordinates | 
Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.
      
  | 
  pure virtual | 
Follow a list of waypoints, one after another.
Perform a take off maneuver
| _height | target height that must be reached to consider the take off complete | 
Implemented in grvc::ual::BackendMavros, grvc::ual::BackendDummy, and grvc::ual::BackendLight.
      
  | 
  protected | 
Abort flag If you want your task to be abortable, check its value periodically
      
  | 
  protected | 
Freeze flag When aborting a task, freezes the platform if it is true
      
  | 
  protected | 
Simplest state-machine model: idle/running Implemented via mutex-locking
 1.8.11