47 #include <lib/ecl/geo/geo.h> 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> 55 #define GEOFENCE_FILENAME PX4_STORAGEDIR"/etc/geofence.txt" 69 GF_ALT_MODE_WGS84 = 0,
75 GF_SOURCE_GLOBALPOS = 0,
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);
125 bool isEmpty() {
return _num_polygons == 0; }
127 int getAltitudeMode() {
return _param_gf_altmode.get(); }
128 int getSource() {
return _param_gf_source.get(); }
129 int getGeofenceAction() {
return _param_gf_action.get(); }
131 bool isHomeRequired();
144 float _altitude_min{0.0f};
145 float _altitude_max{0.0f};
149 uint16_t dataman_index;
151 uint16_t vertex_count;
155 PolygonInfo *_polygons{
nullptr};
156 int _num_polygons{0};
158 map_projection_reference_s _projection_reference = {};
171 int _outside_counter{0};
172 uint16_t _update_counter{0};
189 bool checkPolygons(
double lat,
double lon,
float altitude);
197 bool checkAll(
double lat,
double lon,
float altitude);
199 bool checkAll(
const vehicle_global_position_s &global_position);
200 bool checkAll(
const vehicle_global_position_s &global_position,
float baro_altitude_amsl);
206 bool insidePolygon(
const PolygonInfo &polygon,
double lat,
double lon,
float altitude);
213 bool insideCircle(
const PolygonInfo &polygon,
double lat,
double lon,
float altitude);
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