grvc_ual  2.2
An abstraction layer for unmanned aerial vehicles
backend_mavros.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_MAVROS_H
22 #define UAV_ABSTRACTION_LAYER_BACKEND_MAVROS_H
23 
24 #include <thread>
25 #include <vector>
26 #include <Eigen/Core>
27 
28 #include <uav_abstraction_layer/backend.h>
29 #include <ros/ros.h>
30 
31 //Mavros services
32 #include <mavros_msgs/CommandBool.h>
33 #include <mavros_msgs/SetMode.h>
34 
35 //Mavros messages
36 #include <mavros_msgs/State.h>
37 #include <mavros_msgs/ExtendedState.h>
38 #include <mavros_msgs/GlobalPositionTarget.h>
39 #include <geometry_msgs/PoseStamped.h>
40 #include <geometry_msgs/TwistStamped.h>
41 #include <geometry_msgs/TransformStamped.h>
42 #include <tf2_ros/static_transform_broadcaster.h>
43 #include <sensor_msgs/NavSatFix.h>
44 
45 namespace grvc { namespace ual {
46 
47 class HistoryBuffer { // TODO: template? utils?
48 public:
49  void set_size(size_t _size) {
50  std::lock_guard<std::mutex> lock(mutex_);
51  buffer_size_ = _size;
52  buffer_.clear();
53  current_ = 0;
54  }
55 
56  void reset() {
57  std::lock_guard<std::mutex> lock(mutex_);
58  buffer_.clear();
59  current_ = 0;
60  }
61 
62  void update(double _value) {
63  std::lock_guard<std::mutex> lock(mutex_);
64  if (buffer_.size() < buffer_size_) {
65  buffer_.push_back(_value);
66  } else {
67  buffer_[current_] = _value;
68  current_ = (current_ + 1) % buffer_size_;
69  }
70  }
71 
72  bool get_stats(double& _min, double& _mean, double& _max) {
73  std::lock_guard<std::mutex> lock(mutex_);
74  if (buffer_.size() >= buffer_size_) {
75  double min_value = +std::numeric_limits<double>::max();
76  double max_value = -std::numeric_limits<double>::max();
77  double sum = 0;
78  for (int i = 0; i < buffer_.size(); i++) {
79  if (buffer_[i] < min_value) { min_value = buffer_[i]; }
80  if (buffer_[i] > max_value) { max_value = buffer_[i]; }
81  sum += buffer_[i];
82  }
83  _min = min_value;
84  _max = max_value;
85  _mean = sum / buffer_.size();
86  return true;
87  }
88  return false;
89  }
90 
91  bool get_variance(double& _var) {
92  std::lock_guard<std::mutex> lock(mutex_);
93  if (buffer_.size() >= buffer_size_) {
94  double mean = 0;
95  double sum = 0;
96  _var = 0;
97  for (int i = 0; i < buffer_.size(); i++) {
98  sum += buffer_[i];
99  }
100  mean = sum / buffer_.size();
101  for (int i = 0; i < buffer_.size(); i++) {
102  _var += (buffer_[i]-mean)*(buffer_[i]-mean);
103  }
104  return true;
105  }
106  return false;
107  }
108 
109 protected:
110  size_t buffer_size_ = 0;
111  unsigned int current_ = 0;
112  std::vector<double> buffer_;
113  std::mutex mutex_;
114 };
115 
116 class BackendMavros : public Backend {
117 
118 public:
119  BackendMavros();
120  ~BackendMavros();
121 
123  bool isReady() const override;
125  virtual Pose pose() override;
127  virtual Velocity velocity() const override;
129  virtual Odometry odometry() const override;
131  virtual Transform transform() const override;
132 
135  void setPose(const geometry_msgs::PoseStamped& _pose) override;
136 
139  void goToWaypoint(const Waypoint& _wp) override;
140 
143  void goToWaypointGeo(const WaypointGeo& _wp);
144 
146  // void trackPath(const Path& _path) override;
149  void takeOff(double _height) override;
151  void land() override;
154  void setVelocity(const Velocity& _vel) override;
157  void recoverFromManual() override;
159  void setHome(bool set_z) override;
160 
161 private:
162  void offboardThreadLoop();
163  void initHomeFrame();
164  bool referencePoseReached();
165  void setFlightMode(const std::string& _flight_mode);
166  double updateParam(const std::string& _param_id);
167  State guessState();
168 
169  //WaypointList path_;
170  geometry_msgs::PoseStamped ref_pose_;
171  sensor_msgs::NavSatFix ref_pose_global_;
172  geometry_msgs::PoseStamped cur_pose_;
173  sensor_msgs::NavSatFix cur_geo_pose_;
174  geometry_msgs::TwistStamped ref_vel_;
175  geometry_msgs::TwistStamped cur_vel_;
176  mavros_msgs::State mavros_state_;
177  mavros_msgs::ExtendedState mavros_extended_state_;
178 
179  //Control
180  enum class eControlMode {LOCAL_VEL, LOCAL_POSE, GLOBAL_POSE};
181  eControlMode control_mode_ = eControlMode::LOCAL_POSE;
182  bool mavros_has_pose_ = false;
183  bool mavros_has_geo_pose_ = false;
184  float position_th_;
185  float orientation_th_;
186  HistoryBuffer position_error_;
187  HistoryBuffer orientation_error_;
188 
190  ros::ServiceClient flight_mode_client_;
191  ros::ServiceClient arming_client_;
192  ros::ServiceClient get_param_client_;
193  ros::Publisher mavros_ref_pose_pub_;
194  ros::Publisher mavros_ref_pose_global_pub_;
195  ros::Publisher mavros_ref_vel_pub_;
196  ros::Subscriber mavros_cur_pose_sub_;
197  ros::Subscriber mavros_cur_geo_pose_sub_;
198  ros::Subscriber mavros_cur_vel_sub_;
199  ros::Subscriber mavros_cur_state_sub_;
200  ros::Subscriber mavros_cur_extended_state_sub_;
201 
202  int robot_id_;
203  std::string pose_frame_id_;
204  std::string uav_home_frame_id_;
205  std::string uav_frame_id_;
206  tf2_ros::StaticTransformBroadcaster * static_tf_broadcaster_;
207  std::map <std::string, geometry_msgs::TransformStamped> cached_transforms_;
208  std::map<std::string, double> mavros_params_;
209  Eigen::Vector3d local_start_pos_;
210  ros::Time last_command_time_;
211 
212  std::thread offboard_thread_;
213  double offboard_thread_frequency_;
214 
215  bool calling_takeoff = false;
216  bool calling_land = false;
217 };
218 
219 }} // namespace grvc::ual
220 
221 #endif // UAV_ABSTRACTION_LAYER_BACKEND_MAVROS_H
State
Possible backend states.
Definition: backend.h:65
Common interface for back-end implementations of ual.
Definition: backend.h:46
Definition: backend_mavros.h:116
Definition: backend.h:36
Definition: backend_mavros.h:47