2012-07-14 23:26:17 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
|
|
|
|
/// @file limits.h
|
|
|
|
/// @brief Imposes limits on location (geofence), altitude and other parameters.
|
|
|
|
/// Each limit breach will trigger an action or set of actions to recover. Adapted from geofence.
|
|
|
|
/// @author Andrew Tridgell
|
|
|
|
/// Andreas Antonopoulos
|
|
|
|
|
2012-10-11 22:35:35 -03:00
|
|
|
#ifndef __AP_LIMIT_GEOFENCE_H__
|
|
|
|
#define __AP_LIMIT_GEOFENCE_H__
|
|
|
|
|
|
|
|
#include "AP_Limits.h"
|
|
|
|
#include "AP_Limit_Module.h"
|
2012-07-14 23:26:17 -03:00
|
|
|
#include <AP_Math.h>
|
|
|
|
#include <AP_Param.h>
|
2012-10-11 22:35:35 -03:00
|
|
|
#include <GPS.h>
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-10-11 22:35:35 -03:00
|
|
|
#define MAX_FENCEPOINTS 6
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-08-17 03:20:06 -03:00
|
|
|
class AP_Limit_Geofence : public AP_Limit_Module {
|
2012-07-14 23:26:17 -03:00
|
|
|
|
|
|
|
public:
|
2013-03-26 08:58:54 -03:00
|
|
|
AP_Limit_Geofence(uint16_t eeprom_fence_start, uint8_t fpsize, uint8_t max_fp, GPS *&gps, const struct Location *home_loc, const struct Location *current_loc);
|
2012-08-17 03:20:06 -03:00
|
|
|
bool init();
|
|
|
|
bool triggered();
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-08-17 03:20:06 -03:00
|
|
|
AP_Int8 fence_total();
|
|
|
|
void set_fence_point_with_index(Vector2l &point, uint8_t i);
|
|
|
|
Vector2l get_fence_point_with_index(uint8_t i);
|
|
|
|
void update_boundary();
|
|
|
|
bool boundary_correct();
|
2012-07-14 23:26:17 -03:00
|
|
|
|
|
|
|
|
|
|
|
|
2012-08-17 03:20:06 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-07-14 23:26:17 -03:00
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2012-08-17 03:20:06 -03:00
|
|
|
// pointers to gps, current location and home
|
|
|
|
GPS *& _gps;
|
2013-03-26 08:58:54 -03:00
|
|
|
const struct Location * _current_loc;
|
|
|
|
const struct Location * _home;
|
2012-07-14 23:26:17 -03:00
|
|
|
|
|
|
|
|
2012-08-17 03:20:06 -03:00
|
|
|
// Simple mode, just radius
|
|
|
|
AP_Int8 _simple; // 1 = simple, 0 = complex
|
|
|
|
AP_Int16 _radius; // in meters, for simple mode
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-08-17 03:20:06 -03:00
|
|
|
// Complex mode, defined fence points
|
|
|
|
AP_Int8 _fence_total;
|
|
|
|
AP_Int8 _num_points;
|
2012-07-14 23:26:17 -03:00
|
|
|
|
|
|
|
private:
|
2012-12-13 16:02:19 -04:00
|
|
|
const uint16_t _eeprom_fence_start;
|
2012-08-17 03:20:06 -03:00
|
|
|
const unsigned _fence_wp_size;
|
|
|
|
const unsigned _max_fence_points;
|
|
|
|
bool _boundary_uptodate;
|
|
|
|
Vector2l _boundary[MAX_FENCEPOINTS]; // complex mode fence
|
2012-07-14 23:26:17 -03:00
|
|
|
|
|
|
|
};
|
|
|
|
|
2012-10-11 22:35:35 -03:00
|
|
|
#endif // __AP_LIMIT_GEOFENCE_H__
|