grvc_ual  2.2
An abstraction layer for unmanned aerial vehicles
backend.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_BACKEND_H
22 #define UAV_ABSTRACTION_LAYER_BACKEND_H
23 
24 #include <thread>
25 #include <atomic>
26 #include <mutex>
27 #include <std_msgs/Float32.h>
28 #include <geometry_msgs/Vector3Stamped.h>
29 #include <geometry_msgs/TwistStamped.h>
30 #include <geometry_msgs/PoseStamped.h>
31 #include <geometry_msgs/TransformStamped.h>
32 #include <sensor_msgs/NavSatFix.h>
33 #include <nav_msgs/Odometry.h>
34 // #include <nav_msgs/Path.h>
35 
36 namespace grvc { namespace ual {
37 
38 typedef geometry_msgs::PoseStamped Pose;
39 typedef geometry_msgs::PoseStamped Waypoint;
40 typedef sensor_msgs::NavSatFix WaypointGeo;
41 typedef geometry_msgs::TwistStamped Velocity;
42 typedef nav_msgs::Odometry Odometry;
43 typedef geometry_msgs::TransformStamped Transform;
44 
46 class Backend {
47 public:
48 
50  template <typename Callable, typename ... Args>
51  inline bool threadSafeCall(Callable&& _fn, Args&& ... _args) {
52  // Only one thread can lock
53  if (running_mutex_.try_lock()) {
54  running_task_ = true; // set running after locking
55  std::bind(_fn, this, std::forward<Args>(_args)...)();
56  running_mutex_.unlock();
57  running_task_ = false; // reset it after unlocking
58  return true; // Call succeeded
59  } else {
60  return false; // Call failed
61  }
62  }
63 
65  enum State {
66  UNINITIALIZED,
67  LANDED_DISARMED,
68  LANDED_ARMED,
69  TAKING_OFF,
70  FLYING_AUTO,
71  FLYING_MANUAL,
72  LANDING
73  };
74 
76  Backend();
77 
79  virtual bool isReady() const = 0;
81  bool isIdle();
83  virtual Pose pose() = 0;
85  virtual Velocity velocity() const = 0;
87  virtual Odometry odometry() const = 0;
89  virtual Transform transform() const = 0;
91  inline State state() { return this->state_; }
92 
95  virtual void setPose(const geometry_msgs::PoseStamped& _pose) = 0;
96 
99  virtual void goToWaypoint(const Waypoint& _wp) = 0;
100 
103  virtual void goToWaypointGeo(const WaypointGeo& _wp) = 0;
104 
106  // virtual void trackPath(const Path& _path) = 0;
109  virtual void takeOff(double _height) = 0;
111  virtual void land() = 0;
114  virtual void setVelocity(const Velocity& _vel) = 0;
117  virtual void recoverFromManual() = 0;
119  virtual void setHome(bool set_z) = 0;
120 
122  void abort(bool _freeze = true);
123 
124  virtual ~Backend() = default; // Ensure proper destructor calling for derived classes
125 
133  static Backend* createBackend();
134 
135 protected:
138  std::atomic<bool> abort_ = {false};
139 
142  std::atomic<bool> freeze_ = {false};
143 
146  std::mutex running_mutex_;
147  std::atomic<bool> running_task_ = {false};
148 
149  // Ros spinning thread
150  std::thread spin_thread_;
151 
152  std::atomic<State> state_ = {UNINITIALIZED};
153 };
154 
155 }} // namespace grvc::ual
156 
157 #endif // UAV_ABSTRACTION_LAYER_BACKEND_H
virtual Transform transform() const =0
Latest transform estimation of the robot.
bool isIdle()
Is it idle?
State state()
Current robot state.
Definition: backend.h:91
bool threadSafeCall(Callable &&_fn, Args &&..._args)
Wrap a Backend function to make it thread-safe.
Definition: backend.h:51
std::atomic< bool > freeze_
Definition: backend.h:142
State
Possible backend states.
Definition: backend.h:65
virtual Pose pose()=0
Latest pose estimation of the robot.
virtual void goToWaypointGeo(const WaypointGeo &_wp)=0
virtual Velocity velocity() const =0
Latest velocity estimation of the robot.
virtual void setPose(const geometry_msgs::PoseStamped &_pose)=0
virtual void setHome(bool set_z)=0
Set home position.
virtual bool isReady() const =0
Backend is initialized and ready to run tasks?
virtual void setVelocity(const Velocity &_vel)=0
Common interface for back-end implementations of ual.
Definition: backend.h:46
static Backend * createBackend()
Create an adequate Backend depending on current platform and command arguments.
void abort(bool _freeze=true)
Cancel execution of the current task.
virtual void land()=0
Land on the current position.
virtual void recoverFromManual()=0
virtual void goToWaypoint(const Waypoint &_wp)=0
std::atomic< bool > abort_
Definition: backend.h:138
virtual Odometry odometry() const =0
Latest odometry estimation of the robot.
Definition: backend.h:36
virtual void takeOff(double _height)=0
Follow a list of waypoints, one after another.
std::mutex running_mutex_
Definition: backend.h:146
Backend()
Constructor inits node.