grvc_ual  2.2
An abstraction layer for unmanned aerial vehicles
backend_dummy.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_DUMMY_H
22 #define UAV_ABSTRACTION_LAYER_BACKEND_DUMMY_H
23 
24 #include <uav_abstraction_layer/backend.h>
25 #include <ros/ros.h>
26 
27 
28 namespace grvc { namespace ual {
29 
30 class BackendDummy : public Backend {
31 
32 public:
33  BackendDummy() : Backend() {
34  ROS_WARN("BackendDummy is only for testing porposes");
35  }
36 
38  bool isReady() const override { return true; }
40  virtual Pose pose() override { return Pose(); } // TODO: Never moving?
42  virtual Velocity velocity() const override { return Velocity(); } // TODO: Never moving?
44  virtual Odometry odometry() const override { return Odometry(); } // TODO: Never moving?
46  virtual Transform transform() const override { // TODO: Never moving?
47  Transform out;
48  out.header.stamp = ros::Time::now();
49  out.header.frame_id = "uav_1_home"; // TODO: uav_id?
50  out.child_frame_id = "uav_1"; // TODO: uav_id?
51  out.transform.translation.x = 0;
52  out.transform.translation.y = 0;
53  out.transform.translation.z = 0;
54  out.transform.rotation.x = 0;
55  out.transform.rotation.y = 0;
56  out.transform.rotation.z = 0;
57  out.transform.rotation.w = 1;
58  return out;
59  }
60 
63  void setPose(const geometry_msgs::PoseStamped& _pose) override {
64  ROS_INFO("BackendDummy::setPose: p.x = %f, p.y = %f, p.z = %f, q.x = %f, q.y = %f, q.z = %f, q.w = %f", _pose.pose.position.x, _pose.pose.position.y, _pose.pose.position.z,
65  _pose.pose.orientation.x, _pose.pose.orientation.y, _pose.pose.orientation.z, _pose.pose.orientation.w);
66  }
67 
70  void goToWaypoint(const Waypoint& _wp) override {
71  double yaw = 2 * atan2(_wp.pose.orientation.z, _wp.pose.orientation.w);
72  ROS_INFO("BackendDummy::goToWaypoint: x = %f, y = %f, z = %f, yaw = %f", _wp.pose.position.x, _wp.pose.position.y, _wp.pose.position.z, yaw);
73  }
74 
77  void goToWaypointGeo(const WaypointGeo& _wp) override {
78  ROS_INFO("BackendDummy::goToWaypointGeo: latitude = %f, longitude = %f, altitude = %f", _wp.latitude, _wp.longitude, _wp.altitude);
79  }
80 
82  // void trackPath(const Path& _path) override;
85  void takeOff(double _height) override {
86  ROS_INFO("BackendDummy::takeOff: height = %f", _height);
87  }
89  void land() override {
90  ROS_INFO("BackendDummy::land");
91  }
94  void setVelocity(const Velocity& _vel) override {
95  ROS_INFO("BackendDummy::setVelocity: vx = %f, vy = %f, vz = %f, wz = %f", _vel.twist.linear.x, _vel.twist.linear.y, _vel.twist.linear.z, _vel.twist.angular.z);
96  }
99  void recoverFromManual() override {
100  ROS_INFO("BackendDummy::recoverFromManual");
101  }
103  void setHome(bool set_z) override {
104  ROS_INFO("BackendDummy::setHome: set_z = %s", set_z ? "true" : "false");
105  }
106 };
107 
108 }} // namespace grvc::ual
109 
110 #endif // UAV_ABSTRACTION_LAYER_BACKEND_DUMMY_H
void setPose(const geometry_msgs::PoseStamped &_pose) override
Definition: backend_dummy.h:63
void setVelocity(const Velocity &_vel) override
Definition: backend_dummy.h:94
virtual Odometry odometry() const override
Latest odometry estimation of the robot.
Definition: backend_dummy.h:44
void land() override
Land on the current position.
Definition: backend_dummy.h:89
void takeOff(double _height) override
Follow a list of waypoints, one after another.
Definition: backend_dummy.h:85
virtual Transform transform() const override
Latest transform estimation of the robot.
Definition: backend_dummy.h:46
void recoverFromManual() override
Definition: backend_dummy.h:99
Common interface for back-end implementations of ual.
Definition: backend.h:46
void setHome(bool set_z) override
Set home position.
Definition: backend_dummy.h:103
void goToWaypointGeo(const WaypointGeo &_wp) override
Definition: backend_dummy.h:77
Definition: backend_dummy.h:30
void goToWaypoint(const Waypoint &_wp) override
Definition: backend_dummy.h:70
Definition: backend.h:36
bool isReady() const override
Backend is initialized and ready to run tasks?
Definition: backend_dummy.h:38
virtual Velocity velocity() const override
Latest velocity estimation of the robot.
Definition: backend_dummy.h:42
Backend()
Constructor inits node.
virtual Pose pose() override
Latest pose estimation of the robot.
Definition: backend_dummy.h:40