Firmware
geofence.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
41 #pragma once
42 
43 #include <float.h>
44 
45 #include <px4_module_params.h>
46 #include <drivers/drv_hrt.h>
47 #include <lib/ecl/geo/geo.h>
48 #include <px4_defines.h>
49 #include <uORB/Subscription.hpp>
50 #include <uORB/topics/home_position.h>
51 #include <uORB/topics/vehicle_global_position.h>
52 #include <uORB/topics/vehicle_gps_position.h>
53 #include <uORB/topics/vehicle_air_data.h>
54 
55 #define GEOFENCE_FILENAME PX4_STORAGEDIR"/etc/geofence.txt"
56 
57 class Navigator;
58 
59 class Geofence : public ModuleParams
60 {
61 public:
63  Geofence(const Geofence &) = delete;
64  Geofence &operator=(const Geofence &) = delete;
65  ~Geofence();
66 
67  /* Altitude mode, corresponding to the param GF_ALTMODE */
68  enum {
69  GF_ALT_MODE_WGS84 = 0,
70  GF_ALT_MODE_AMSL = 1
71  };
72 
73  /* Source, corresponding to the param GF_SOURCE */
74  enum {
75  GF_SOURCE_GLOBALPOS = 0,
76  GF_SOURCE_GPS = 1
77  };
78 
83  void updateFence();
84 
90  bool check(const vehicle_global_position_s &global_position,
91  const vehicle_gps_position_s &gps_position, const home_position_s home_pos, bool home_position_set);
92 
98  bool check(const struct mission_item_s &mission_item);
99 
100  int clearDm();
101 
102  bool valid();
103 
123  int loadFromFile(const char *filename);
124 
125  bool isEmpty() { return _num_polygons == 0; }
126 
127  int getAltitudeMode() { return _param_gf_altmode.get(); }
128  int getSource() { return _param_gf_source.get(); }
129  int getGeofenceAction() { return _param_gf_action.get(); }
130 
131  bool isHomeRequired();
132 
136  void printStatus();
137 
138 private:
139  Navigator *_navigator{nullptr};
140 
141  hrt_abstime _last_horizontal_range_warning{0};
142  hrt_abstime _last_vertical_range_warning{0};
143 
144  float _altitude_min{0.0f};
145  float _altitude_max{0.0f};
146 
147  struct PolygonInfo {
148  uint16_t fence_type;
149  uint16_t dataman_index;
150  union {
151  uint16_t vertex_count;
152  float circle_radius;
153  };
154  };
155  PolygonInfo *_polygons{nullptr};
156  int _num_polygons{0};
157 
158  map_projection_reference_s _projection_reference = {};
159 
160  DEFINE_PARAMETERS(
161  (ParamInt<px4::params::GF_ACTION>) _param_gf_action,
162  (ParamInt<px4::params::GF_ALTMODE>) _param_gf_altmode,
163  (ParamInt<px4::params::GF_SOURCE>) _param_gf_source,
164  (ParamInt<px4::params::GF_COUNT>) _param_gf_count,
165  (ParamFloat<px4::params::GF_MAX_HOR_DIST>) _param_gf_max_hor_dist,
166  (ParamFloat<px4::params::GF_MAX_VER_DIST>) _param_gf_max_ver_dist
167  )
168 
170 
171  int _outside_counter{0};
172  uint16_t _update_counter{0};
173 
177  void _updateFence();
178 
189  bool checkPolygons(double lat, double lon, float altitude);
190 
197  bool checkAll(double lat, double lon, float altitude);
198 
199  bool checkAll(const vehicle_global_position_s &global_position);
200  bool checkAll(const vehicle_global_position_s &global_position, float baro_altitude_amsl);
201 
206  bool insidePolygon(const PolygonInfo &polygon, double lat, double lon, float altitude);
207 
213  bool insideCircle(const PolygonInfo &polygon, double lat, double lon, float altitude);
214 };
Global position setpoint in WGS84 coordinates.
Definition: navigation.h:145
int loadFromFile(const char *filename)
Load a single inclusion polygon, replacing any already existing polygons.
Definition: geofence.cpp:436
Definition: navigator_main.cpp:80
High-resolution timer with callouts and timekeeping.
Generally used magic defines.
Definition: px4_param.h:318
C++ base class for modules/classes using configuration parameters.
Definition: px4_module_params.h:46
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Definition: navigator.h:83
void printStatus()
print Geofence status to the console
Definition: geofence.cpp:578
bool check(const vehicle_global_position_s &global_position, const vehicle_gps_position_s &gps_position, const home_position_s home_pos, bool home_position_set)
Return whether the system obeys the geofence.
Definition: geofence.cpp:190
Definition: geofence.h:59
void updateFence()
update the geofence from dataman.
Definition: geofence.cpp:71