APM:Libraries
AP_Beacon.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
22 
23 class AP_Beacon_Backend;
24 
25 #define AP_BEACON_MAX_BEACONS 4
26 #define AP_BEACON_TIMEOUT_MS 300
27 #define AP_BEACON_MINIMUM_FENCE_BEACONS 3
28 
29 class AP_Beacon
30 {
31 public:
32  friend class AP_Beacon_Backend;
33 
34  AP_Beacon(AP_SerialManager &_serial_manager);
35 
36  // external position backend types (used by _TYPE parameter)
42  };
43 
44  // The AP_BeaconState structure is filled in by the backend driver
45  struct BeaconState {
46  uint16_t id; // unique id of beacon
47  bool healthy; // true if beacon is healthy
48  float distance; // distance from vehicle to beacon (in meters)
49  uint32_t distance_update_ms; // system time of last update from this beacon
50  Vector3f position; // location of beacon as an offset from origin in NED in meters
51  };
52 
53  // initialise any available position estimators
54  void init(void);
55 
56  // return true if beacon feature is enabled
57  bool enabled(void);
58 
59  // return true if sensor is basically healthy (we are receiving data)
60  bool healthy(void);
61 
62  // update state of all beacons
63  void update(void);
64 
65  // return origin of position estimate system in lat/lon
66  bool get_origin(Location &origin_loc) const;
67 
68  // return vehicle position in NED from position estimate system's origin in meters
69  bool get_vehicle_position_ned(Vector3f& pos, float& accuracy_estimate) const;
70 
71  // return the number of beacons
72  uint8_t count() const;
73 
74  // methods to return beacon specific information
75 
76  // return all beacon data
77  bool get_beacon_data(uint8_t beacon_instance, struct BeaconState& state) const;
78 
79  // return individual beacon's id
80  uint8_t beacon_id(uint8_t beacon_instance) const;
81 
82  // return beacon health
83  bool beacon_healthy(uint8_t beacon_instance) const;
84 
85  // return distance to beacon in meters
86  float beacon_distance(uint8_t beacon_instance) const;
87 
88  // return NED position of beacon in meters relative to the beacon systems origin
89  Vector3f beacon_position(uint8_t beacon_instance) const;
90 
91  // return last update time from beacon in milliseconds
92  uint32_t beacon_last_update_ms(uint8_t beacon_instance) const;
93 
94  // update fence boundary array
96 
97  // return fence boundary array
98  const Vector2f* get_boundary_points(uint16_t& num_points) const;
99 
100  static const struct AP_Param::GroupInfo var_info[];
101 
102 private:
103 
104  // check if device is ready
105  bool device_ready(void) const;
106 
107  // find next boundary point from an array of boundary points given the current index into that array
108  // returns true if a next point can be found
109  // current_index should be an index into the boundary_pts array
110  // start_angle is an angle (in radians), the search will sweep clockwise from this angle
111  // the index of the next point is returned in the next_index argument
112  // the angle to the next point is returned in the next_angle argument
113  static bool get_next_boundary_point(const Vector2f* boundary, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t& next_index, float& next_angle);
114 
115  // parameters
116  AP_Int8 _type;
117  AP_Float origin_lat;
118  AP_Float origin_lon;
119  AP_Float origin_alt;
120  AP_Int16 orient_yaw;
121 
122  // external references
125 
126  // last known position
130 
131  // individual beacon data
132  uint8_t num_beacons = 0;
134 
135  // fence boundary
136  Vector2f boundary[AP_BEACON_MAX_BEACONS+1]; // array of boundary points (used for fence)
137  uint8_t boundary_num_points; // number of points in boundary
138  uint8_t boundary_num_beacons; // total number of beacon points consumed while building boundary
139 };
float veh_pos_accuracy
Definition: AP_Beacon.h:128
bool device_ready(void) const
Definition: AP_Beacon.cpp:373
float beacon_distance(uint8_t beacon_instance) const
Definition: AP_Beacon.cpp:204
const Vector2f * get_boundary_points(uint16_t &num_points) const
Definition: AP_Beacon.cpp:361
void init(void)
Definition: AP_Beacon.cpp:80
AP_Beacon(AP_SerialManager &_serial_manager)
Definition: AP_Beacon.cpp:73
#define AP_BEACON_MAX_BEACONS
Definition: AP_Beacon.h:25
AP_Float origin_lat
Definition: AP_Beacon.h:117
AP_Int16 orient_yaw
Definition: AP_Beacon.h:120
AP_SerialManager & serial_manager
Definition: AP_Beacon.h:124
static bool get_next_boundary_point(const Vector2f *boundary, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t &next_index, float &next_angle)
Definition: AP_Beacon.cpp:321
bool beacon_healthy(uint8_t beacon_instance) const
Definition: AP_Beacon.cpp:195
AP_Float origin_alt
Definition: AP_Beacon.h:119
uint32_t distance_update_ms
Definition: AP_Beacon.h:49
A system for managing and storing variables that are of general interest to the system.
bool get_origin(Location &origin_loc) const
Definition: AP_Beacon.cpp:128
uint8_t beacon_id(uint8_t beacon_instance) const
Definition: AP_Beacon.cpp:186
bool get_vehicle_position_ned(Vector3f &pos, float &accuracy_estimate) const
Definition: AP_Beacon.cpp:149
bool enabled(void)
Definition: AP_Beacon.cpp:101
Vector2f boundary[AP_BEACON_MAX_BEACONS+1]
Definition: AP_Beacon.h:136
uint8_t num_beacons
Definition: AP_Beacon.h:132
Vector3f beacon_position(uint8_t beacon_instance) const
Definition: AP_Beacon.cpp:213
AP_Beacon_Backend * _driver
Definition: AP_Beacon.h:123
static int state
Definition: Util.cpp:20
uint32_t veh_pos_update_ms
Definition: AP_Beacon.h:129
bool get_beacon_data(uint8_t beacon_instance, struct BeaconState &state) const
Definition: AP_Beacon.cpp:176
uint32_t beacon_last_update_ms(uint8_t beacon_instance) const
Definition: AP_Beacon.cpp:223
Common definitions and utility routines for the ArduPilot libraries.
uint8_t boundary_num_points
Definition: AP_Beacon.h:137
void update(void)
Definition: AP_Beacon.cpp:116
Vector3f veh_pos_ned
Definition: AP_Beacon.h:127
uint8_t boundary_num_beacons
Definition: AP_Beacon.h:138
BeaconState beacon_state[AP_BEACON_MAX_BEACONS]
Definition: AP_Beacon.h:133
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Beacon.h:100
AP_Int8 _type
Definition: AP_Beacon.h:116
AP_Float origin_lon
Definition: AP_Beacon.h:118
uint8_t count() const
Definition: AP_Beacon.cpp:167
void update_boundary_points()
Definition: AP_Beacon.cpp:232