21 #ifndef UAV_ABSTRACTION_LAYER_BACKEND_H 22 #define UAV_ABSTRACTION_LAYER_BACKEND_H 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> 36 namespace grvc {
namespace ual {
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;
50 template <
typename Callable,
typename ... Args>
55 std::bind(_fn,
this, std::forward<Args>(_args)...)();
57 running_task_ =
false;
79 virtual bool isReady()
const = 0;
83 virtual Pose
pose() = 0;
85 virtual Velocity
velocity()
const = 0;
87 virtual Odometry
odometry()
const = 0;
95 virtual void setPose(
const geometry_msgs::PoseStamped& _pose) = 0;
109 virtual void takeOff(
double _height) = 0;
111 virtual void land() = 0;
114 virtual void setVelocity(
const Velocity& _vel) = 0;
119 virtual void setHome(
bool set_z) = 0;
122 void abort(
bool _freeze =
true);
147 std::atomic<bool> running_task_ = {
false};
150 std::thread spin_thread_;
152 std::atomic<State> state_ = {UNINITIALIZED};
157 #endif // UAV_ABSTRACTION_LAYER_BACKEND_H virtual Transform transform() const =0
Latest transform estimation of the robot.
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.
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.