PX4 Firmware
PX4 Autopilot Software http://px4.io
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  ****************************************************************************/
33 /**
34  * @file geofence.h
35  * Provides functions for handling the geofence
36  *
37  * @author Jean Cyr <jean.m.cyr@gmail.com>
38  * @author Thomas Gubler <thomasgubler@gmail.com>
39  */
40 
41 #pragma once
42 
43 #include <float.h>
44 
45 #include <px4_platform_common/module_params.h>
46 #include <drivers/drv_hrt.h>
47 #include <lib/ecl/geo/geo.h>
48 #include <px4_platform_common/defines.h>
49 #include <uORB/Subscription.hpp>
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 {
71  };
72 
73  /* Source, corresponding to the param GF_SOURCE */
74  enum {
77  };
78 
79  /**
80  * update the geofence from dataman.
81  * It's generally not necessary to call this as it will automatically update when the data is changed.
82  */
83  void updateFence();
84 
85  /**
86  * Return whether the system obeys the geofence.
87  *
88  * @return true: system is obeying fence, false: system is violating fence
89  */
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 
93  /**
94  * Return whether a mission item obeys the geofence.
95  *
96  * @return true: system is obeying fence, false: system is violating fence
97  */
98  bool check(const struct mission_item_s &mission_item);
99 
100  int clearDm();
101 
102  bool valid();
103 
104  /**
105  * Load a single inclusion polygon, replacing any already existing polygons.
106  * The file has one of the following formats:
107  * - Decimal Degrees:
108  * 0 900
109  * 47.475273548913222 8.52672100067138672
110  * 47.4608261578541359 8.53414535522460938
111  * 47.4613484218861217 8.56444358825683594
112  * 47.4830758091035534 8.53470325469970703
113  *
114  * - Degree-Minute-Second:
115  * 0 900
116  * DMS -26 -34 -10.4304 151 50 14.5428
117  * DMS -26 -34 -11.8416 151 50 21.8580
118  * DMS -26 -34 -36.5628 151 50 28.1112
119  * DMS -26 -34 -37.1640 151 50 24.1620
120  *
121  * Where the first line is min, max altitude in meters AMSL.
122  */
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 
133  /**
134  * print Geofence status to the console
135  */
136  void printStatus();
137 
138 private:
140 
143 
144  float _altitude_min{0.0f};
145  float _altitude_max{0.0f};
146 
147  struct PolygonInfo {
148  uint16_t fence_type; ///< one of MAV_CMD_NAV_FENCE_* (can also be a circular region)
149  uint16_t dataman_index;
150  union {
151  uint16_t vertex_count;
153  };
154  };
157 
158  map_projection_reference_s _projection_reference = {}; ///< reference to convert (lon, lat) to local [m]
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 
172  uint16_t _update_counter{0}; ///< dataman update counter: if it does not match, we polygon data was updated
173 
174  /**
175  * implementation of updateFence(), but without locking
176  */
177  void _updateFence();
178 
179  /**
180  * Check if a point passes the Geofence test.
181  * This takes all polygons and minimum & maximum altitude into account
182  *
183  * The check passes if: (inside(polygon_inclusion_1) || inside(polygon_inclusion_2) || ... ) &&
184  * !inside(polygon_exclusion_1) && !inside(polygon_exclusion_2) && ...
185  * && (altitude within [min, max])
186  * or: no polygon configured
187  * @return result of the check above (false for a geofence violation)
188  */
189  bool checkPolygons(double lat, double lon, float altitude);
190 
191  /**
192  * Check if a point passes the Geofence test.
193  * In addition to checkPolygons(), this takes all additional parameters into account.
194  *
195  * @return false for a geofence violation
196  */
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 
202  /**
203  * Check if a single point is within a polygon
204  * @return true if within polygon
205  */
206  bool insidePolygon(const PolygonInfo &polygon, double lat, double lon, float altitude);
207 
208  /**
209  * Check if a single point is within a circle
210  * @param polygon must be a circle!
211  * @return true if within polygon the circle
212  */
213  bool insideCircle(const PolygonInfo &polygon, double lat, double lon, float altitude);
214 };
void _updateFence()
implementation of updateFence(), but without locking
Definition: geofence.cpp:86
bool insideCircle(const PolygonInfo &polygon, double lat, double lon, float altitude)
Check if a single point is within a circle.
Definition: geofence.cpp:399
Global position setpoint in WGS84 coordinates.
Definition: navigation.h:145
float _altitude_max
Definition: geofence.h:145
Definition of geo / math functions to perform geodesic calculations.
hrt_abstime _last_vertical_range_warning
Definition: geofence.h:142
bool valid()
Definition: geofence.cpp:430
bool checkAll(double lat, double lon, float altitude)
Check if a point passes the Geofence test.
Definition: geofence.cpp:221
PolygonInfo * _polygons
Definition: geofence.h:155
int getAltitudeMode()
Definition: geofence.h:127
bool isEmpty()
Definition: geofence.h:125
bool insidePolygon(const PolygonInfo &polygon, double lat, double lon, float altitude)
Check if a single point is within a polygon.
Definition: geofence.cpp:357
hrt_abstime _last_horizontal_range_warning
Definition: geofence.h:141
uint16_t fence_type
one of MAV_CMD_NAV_FENCE_* (can also be a circular region)
Definition: geofence.h:148
void updateFence()
update the geofence from dataman.
Definition: geofence.cpp:71
void printStatus()
print Geofence status to the console
Definition: geofence.cpp:578
High-resolution timer with callouts and timekeeping.
int getGeofenceAction()
Definition: geofence.h:129
Geofence(Navigator *navigator)
Definition: geofence.cpp:55
map_projection_reference_s _projection_reference
reference to convert (lon, lat) to local [m]
Definition: geofence.h:158
DEFINE_PARAMETERS((ParamInt< px4::params::GF_ACTION >) _param_gf_action,(ParamInt< px4::params::GF_ALTMODE >) _param_gf_altmode,(ParamInt< px4::params::GF_SOURCE >) _param_gf_source,(ParamInt< px4::params::GF_COUNT >) _param_gf_count,(ParamFloat< px4::params::GF_MAX_HOR_DIST >) _param_gf_max_hor_dist,(ParamFloat< px4::params::GF_MAX_VER_DIST >) _param_gf_max_ver_dist) uORB int _outside_counter
Definition: geofence.h:171
Navigator * _navigator
Definition: geofence.h:139
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
int clearDm()
Definition: geofence.cpp:562
bool checkPolygons(double lat, double lon, float altitude)
Check if a point passes the Geofence test.
Definition: geofence.cpp:281
~Geofence()
Definition: geofence.cpp:64
int _num_polygons
Definition: geofence.h:156
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Geofence & operator=(const Geofence &)=delete
int loadFromFile(const char *filename)
Load a single inclusion polygon, replacing any already existing polygons.
Definition: geofence.cpp:436
uint16_t dataman_index
Definition: geofence.h:149
bool isHomeRequired()
Definition: geofence.cpp:569
uint16_t vertex_count
Definition: geofence.h:151
uint16_t _update_counter
dataman update counter: if it does not match, we polygon data was updated
Definition: geofence.h:172
float _altitude_min
Definition: geofence.h:144
int getSource()
Definition: geofence.h:128