CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Beacon/AP_Beacon.h
Views: 1798
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_Beacon_config.h"
18
19
#if AP_BEACON_ENABLED
20
21
#include <AP_Common/AP_Common.h>
22
#include <AP_Param/AP_Param.h>
23
#include <AP_Math/AP_Math.h>
24
#include <AP_Common/Location.h>
25
26
class AP_Beacon_Backend;
27
28
class AP_Beacon
29
{
30
public:
31
friend class AP_Beacon_Backend;
32
33
AP_Beacon();
34
35
// get singleton instance
36
static AP_Beacon *get_singleton() { return _singleton; }
37
38
// external position backend types (used by _TYPE parameter)
39
enum class Type : uint8_t {
40
None = 0,
41
Pozyx = 1,
42
Marvelmind = 2,
43
Nooploop = 3,
44
#if AP_BEACON_SITL_ENABLED
45
SITL = 10
46
#endif
47
};
48
49
// The AP_BeaconState structure is filled in by the backend driver
50
struct BeaconState {
51
uint16_t id; // unique id of beacon
52
bool healthy; // true if beacon is healthy
53
float distance; // distance from vehicle to beacon (in meters)
54
uint32_t distance_update_ms; // system time of last update from this beacon
55
Vector3f position; // location of beacon as an offset from origin in NED in meters
56
};
57
58
// initialise any available position estimators
59
void init(void);
60
61
// return true if beacon feature is enabled
62
bool enabled(void) const;
63
64
// return true if sensor is basically healthy (we are receiving data)
65
bool healthy(void) const;
66
67
// update state of all beacons
68
void update(void);
69
70
// return origin of position estimate system in lat/lon
71
bool get_origin(Location &origin_loc) const;
72
73
// return vehicle position in NED from position estimate system's origin in meters
74
bool get_vehicle_position_ned(Vector3f& pos, float& accuracy_estimate) const;
75
76
// return the number of beacons
77
uint8_t count() const;
78
79
// methods to return beacon specific information
80
81
// return all beacon data
82
bool get_beacon_data(uint8_t beacon_instance, struct BeaconState& state) const;
83
84
// return individual beacon's id
85
uint8_t beacon_id(uint8_t beacon_instance) const;
86
87
// return beacon health
88
bool beacon_healthy(uint8_t beacon_instance) const;
89
90
// return distance to beacon in meters
91
float beacon_distance(uint8_t beacon_instance) const;
92
93
// return NED position of beacon in meters relative to the beacon systems origin
94
Vector3f beacon_position(uint8_t beacon_instance) const;
95
96
// return last update time from beacon in milliseconds
97
uint32_t beacon_last_update_ms(uint8_t beacon_instance) const;
98
99
// update fence boundary array
100
void update_boundary_points();
101
102
// return fence boundary array
103
const Vector2f* get_boundary_points(uint16_t& num_points) const;
104
105
static const struct AP_Param::GroupInfo var_info[];
106
107
// a method for vehicles to call to make onboard log messages:
108
void log();
109
110
private:
111
112
static AP_Beacon *_singleton;
113
114
// check if device is ready
115
bool device_ready(void) const;
116
117
// find next boundary point from an array of boundary points given the current index into that array
118
// returns true if a next point can be found
119
// current_index should be an index into the boundary_pts array
120
// start_angle is an angle (in radians), the search will sweep clockwise from this angle
121
// the index of the next point is returned in the next_index argument
122
// the angle to the next point is returned in the next_angle argument
123
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);
124
125
// parameters
126
AP_Enum<Type> _type;
127
AP_Float origin_lat;
128
AP_Float origin_lon;
129
AP_Float origin_alt;
130
AP_Int16 orient_yaw;
131
132
// external references
133
AP_Beacon_Backend *_driver;
134
135
// last known position
136
Vector3f veh_pos_ned;
137
float veh_pos_accuracy;
138
uint32_t veh_pos_update_ms;
139
140
// individual beacon data
141
uint8_t num_beacons = 0;
142
BeaconState beacon_state[AP_BEACON_MAX_BEACONS];
143
144
// fence boundary
145
Vector2f boundary[AP_BEACON_MAX_BEACONS+1]; // array of boundary points (used for fence)
146
uint8_t boundary_num_points; // number of points in boundary
147
uint8_t boundary_num_beacons; // total number of beacon points consumed while building boundary
148
};
149
150
namespace AP {
151
AP_Beacon *beacon();
152
};
153
154
#endif // AP_BEACON_ENABLED
155
156