grvc_ual  2.2
An abstraction layer for unmanned aerial vehicles
ual.h
1 //----------------------------------------------------------------------------------------------------------------------
2 // GRVC UAL
3 //----------------------------------------------------------------------------------------------------------------------
4 // The MIT License (MIT)
5 //
6 // Copyright (c) 2016 GRVC University of Seville
7 //
8 // Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated
9 // documentation files (the "Software"), to deal in the Software without restriction, including without limitation the
10 // rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to
11 // permit persons to whom the Software is furnished to do so, subject to the following conditions:
12 //
13 // The above copyright notice and this permission notice shall be included in all copies or substantial portions of the
14 // Software.
15 //
16 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE
17 // WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS
18 // OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR
19 // OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
20 //----------------------------------------------------------------------------------------------------------------------
21 #ifndef UAV_ABSTRACTION_LAYER_UAL_H
22 #define UAV_ABSTRACTION_LAYER_UAL_H
23 
24 #include <uav_abstraction_layer/backend.h>
25 #include <uav_abstraction_layer/GoToWaypoint.h>
26 #include <uav_abstraction_layer/TakeOff.h>
27 #include <uav_abstraction_layer/Land.h>
28 #include <uav_abstraction_layer/SetVelocity.h>
29 #include <uav_abstraction_layer/State.h>
30 #include <thread>
31 
32 namespace grvc { namespace ual {
33 
35 class UAL {
36 public:
37  UAL(int _argc, char** _argv);
38  UAL();
39  ~UAL();
40 
42  bool isReady() const { return backend_->isReady(); }
43 
45  bool isIdle() const { return backend_->isIdle(); }
46 
48  Pose pose() const { return backend_->pose(); }
49 
51  Velocity velocity() const { return backend_->velocity(); }
52 
54  Odometry odometry() const { return backend_->odometry(); }
55 
57  Transform transform() const { return backend_->transform(); }
58 
60  uav_abstraction_layer::State state();
61 
64  bool setPose(const geometry_msgs::PoseStamped& _pose);
65 
69  bool goToWaypoint(const Waypoint& _wp, bool _blocking = true);
70 
74  bool goToWaypointGeo(const WaypointGeo& _wp, bool _blocking = true);
75 
79  bool takeOff(double _height, bool _blocking = true);
80 
83  bool land(bool _blocking = true);
84 
87  bool setVelocity(const Velocity& _vel);
88 
92  bool recoverFromManual();
93 
95  bool setHome(bool set_z = false);
96 
97 protected:
98  void init();
99  Backend* backend_;
100  std::thread running_thread_;
101  std::thread server_thread_;
102 
103  int robot_id_;
104  bool id_is_unique_;
105 };
106 
107 }} // namespace grvc::ual
108 
109 #endif // UAV_ABSTRACTION_LAYER_UAL_H
virtual Transform transform() const =0
Latest transform estimation of the robot.
uav_abstraction_layer::State state()
Current robot state.
bool recoverFromManual()
bool isIdle()
Is it idle?
bool setVelocity(const Velocity &_vel)
virtual Pose pose()=0
Latest pose estimation of the robot.
virtual Velocity velocity() const =0
Latest velocity estimation of the robot.
Pose pose() const
Latest pose estimation of the robot.
Definition: ual.h:48
bool isIdle() const
Idle?
Definition: ual.h:45
bool isReady() const
Initialized and ready to run tasks?
Definition: ual.h:42
Odometry odometry() const
Latest odometry estimation of the robot.
Definition: ual.h:54
virtual bool isReady() const =0
Backend is initialized and ready to run tasks?
bool goToWaypointGeo(const WaypointGeo &_wp, bool _blocking=true)
Common interface for back-end implementations of ual.
Definition: backend.h:46
Velocity velocity() const
Latest velocity estimation of the robot.
Definition: ual.h:51
Transform transform() const
Latest transform estimation of the robot.
Definition: ual.h:57
bool land(bool _blocking=true)
bool goToWaypoint(const Waypoint &_wp, bool _blocking=true)
virtual Odometry odometry() const =0
Latest odometry estimation of the robot.
Definition: backend.h:36
UAL replicates Backend interface, with some extras.
Definition: ual.h:35
bool takeOff(double _height, bool _blocking=true)
bool setPose(const geometry_msgs::PoseStamped &_pose)
bool setHome(bool set_z=false)
Set home position (Needed to fix px4 local pose drift)