21 #ifndef UAV_ABSTRACTION_LAYER_UAL_H 22 #define UAV_ABSTRACTION_LAYER_UAL_H 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> 32 namespace grvc {
namespace ual {
37 UAL(
int _argc,
char** _argv);
60 uav_abstraction_layer::State
state();
64 bool setPose(
const geometry_msgs::PoseStamped& _pose);
69 bool goToWaypoint(
const Waypoint& _wp,
bool _blocking =
true);
79 bool takeOff(
double _height,
bool _blocking =
true);
83 bool land(
bool _blocking =
true);
95 bool setHome(
bool set_z =
false);
100 std::thread running_thread_;
101 std::thread server_thread_;
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 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.
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)