Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Beacon/AP_Beacon.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_Beacon.h"1617#if AP_BEACON_ENABLED1819#include "AP_Beacon_Backend.h"20#include "AP_Beacon_Pozyx.h"21#include "AP_Beacon_Marvelmind.h"22#include "AP_Beacon_Nooploop.h"23#include "AP_Beacon_SITL.h"2425#include <AP_Common/Location.h>26#include <AP_Logger/AP_Logger.h>2728extern const AP_HAL::HAL &hal;2930#ifndef AP_BEACON_MINIMUM_FENCE_BEACONS31#define AP_BEACON_MINIMUM_FENCE_BEACONS 332#endif3334// table of user settable parameters35const AP_Param::GroupInfo AP_Beacon::var_info[] = {3637// @Param: _TYPE38// @DisplayName: Beacon based position estimation device type39// @Description: What type of beacon based position estimation device is connected40// @Values: 0:None,1:Pozyx,2:Marvelmind,3:Nooploop,10:SITL41// @User: Advanced42AP_GROUPINFO_FLAGS("_TYPE", 0, AP_Beacon, _type, 0, AP_PARAM_FLAG_ENABLE),4344// @Param: _LATITUDE45// @DisplayName: Beacon origin's latitude46// @Description: Beacon origin's latitude47// @Units: deg48// @Increment: 0.00000149// @Range: -90 9050// @User: Advanced51AP_GROUPINFO("_LATITUDE", 1, AP_Beacon, origin_lat, 0),5253// @Param: _LONGITUDE54// @DisplayName: Beacon origin's longitude55// @Description: Beacon origin's longitude56// @Units: deg57// @Increment: 0.00000158// @Range: -180 18059// @User: Advanced60AP_GROUPINFO("_LONGITUDE", 2, AP_Beacon, origin_lon, 0),6162// @Param: _ALT63// @DisplayName: Beacon origin's altitude above sealevel in meters64// @Description: Beacon origin's altitude above sealevel in meters65// @Units: m66// @Increment: 167// @Range: 0 1000068// @User: Advanced69AP_GROUPINFO("_ALT", 3, AP_Beacon, origin_alt, 0),7071// @Param: _ORIENT_YAW72// @DisplayName: Beacon systems rotation from north in degrees73// @Description: Beacon systems rotation from north in degrees74// @Units: deg75// @Increment: 176// @Range: -180 +18077// @User: Advanced78AP_GROUPINFO("_ORIENT_YAW", 4, AP_Beacon, orient_yaw, 0),7980AP_GROUPEND81};8283AP_Beacon::AP_Beacon()84{85#if CONFIG_HAL_BOARD == HAL_BOARD_SITL86if (_singleton != nullptr) {87AP_HAL::panic("Fence must be singleton");88}89#endif90_singleton = this;91AP_Param::setup_object_defaults(this, var_info);92}9394// initialise the AP_Beacon class95void AP_Beacon::init(void)96{97if (_driver != nullptr) {98// init called a 2nd time?99return;100}101102// create backend103switch ((Type)_type) {104case Type::Pozyx:105_driver = NEW_NOTHROW AP_Beacon_Pozyx(*this);106break;107case Type::Marvelmind:108_driver = NEW_NOTHROW AP_Beacon_Marvelmind(*this);109break;110case Type::Nooploop:111_driver = NEW_NOTHROW AP_Beacon_Nooploop(*this);112break;113#if AP_BEACON_SITL_ENABLED114case Type::SITL:115_driver = NEW_NOTHROW AP_Beacon_SITL(*this);116break;117#endif118case Type::None:119break;120}121}122123// return true if beacon feature is enabled124bool AP_Beacon::enabled(void) const125{126return (_type != Type::None);127}128129// return true if sensor is basically healthy (we are receiving data)130bool AP_Beacon::healthy(void) const131{132if (!device_ready()) {133return false;134}135return _driver->healthy();136}137138// update state. This should be called often from the main loop139void AP_Beacon::update(void)140{141if (!device_ready()) {142return;143}144_driver->update();145146// update boundary for fence147update_boundary_points();148}149150// return origin of position estimate system151bool AP_Beacon::get_origin(Location &origin_loc) const152{153if (!device_ready()) {154return false;155}156157// check for un-initialised origin158if (is_zero(origin_lat) && is_zero(origin_lon) && is_zero(origin_alt)) {159return false;160}161162// return origin163origin_loc = {};164origin_loc.lat = origin_lat * 1.0e7f;165origin_loc.lng = origin_lon * 1.0e7f;166origin_loc.alt = origin_alt * 100;167168return true;169}170171// return position in NED from position estimate system's origin in meters172bool AP_Beacon::get_vehicle_position_ned(Vector3f &position, float& accuracy_estimate) const173{174if (!device_ready()) {175return false;176}177178// check for timeout179if (AP_HAL::millis() - veh_pos_update_ms > AP_BEACON_TIMEOUT_MS) {180return false;181}182183// return position184position = veh_pos_ned;185accuracy_estimate = veh_pos_accuracy;186return true;187}188189// return the number of beacons190uint8_t AP_Beacon::count() const191{192if (!device_ready()) {193return 0;194}195return num_beacons;196}197198// return all beacon data199bool AP_Beacon::get_beacon_data(uint8_t beacon_instance, struct BeaconState& state) const200{201if (!device_ready() || beacon_instance >= num_beacons) {202return false;203}204state = beacon_state[beacon_instance];205return true;206}207208// return individual beacon's id209uint8_t AP_Beacon::beacon_id(uint8_t beacon_instance) const210{211if (beacon_instance >= num_beacons) {212return 0;213}214return beacon_state[beacon_instance].id;215}216217// return beacon health218bool AP_Beacon::beacon_healthy(uint8_t beacon_instance) const219{220if (beacon_instance >= num_beacons) {221return false;222}223return beacon_state[beacon_instance].healthy;224}225226// return distance to beacon in meters227float AP_Beacon::beacon_distance(uint8_t beacon_instance) const228{229if ( beacon_instance >= num_beacons || !beacon_state[beacon_instance].healthy) {230return 0.0f;231}232return beacon_state[beacon_instance].distance;233}234235// return beacon position in meters236Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const237{238if (!device_ready() || beacon_instance >= num_beacons) {239Vector3f temp = {};240return temp;241}242return beacon_state[beacon_instance].position;243}244245// return last update time from beacon in milliseconds246uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const247{248if (_type == Type::None || beacon_instance >= num_beacons) {249return 0;250}251return beacon_state[beacon_instance].distance_update_ms;252}253254// create fence boundary points255void AP_Beacon::update_boundary_points()256{257// we need three beacons at least to create boundary fence.258// update boundary fence if number of beacons changes259if (!device_ready() || num_beacons < AP_BEACON_MINIMUM_FENCE_BEACONS || boundary_num_beacons == num_beacons) {260return;261}262263// record number of beacons so we do not repeat calculations264boundary_num_beacons = num_beacons;265266// accumulate beacon points267Vector2f beacon_points[AP_BEACON_MAX_BEACONS];268for (uint8_t index = 0; index < num_beacons; index++) {269const Vector3f& point_3d = beacon_position(index);270beacon_points[index].x = point_3d.x;271beacon_points[index].y = point_3d.y;272}273274// create polygon around boundary points using the following algorithm275// set the "current point" as the first boundary point276// loop through all the boundary points looking for the point which creates a vector (from the current point to this new point) with the lowest angle277// check if point is already in boundary278// - no: add to boundary, move current point to this new point and repeat the above279// - yes: we've completed the bounding box, delete any boundary points found earlier than the duplicate280281Vector2f boundary_points[AP_BEACON_MAX_BEACONS+1]; // array of boundary points282uint8_t curr_boundary_idx = 0; // index into boundary_sorted index. always points to the highest filled in element of the array283uint8_t curr_beacon_idx = 0; // index into beacon_point array. point indexed is same point as curr_boundary_idx's284285// initialise first point of boundary_sorted with first beacon's position (this point may be removed later if it is found to not be on the outer boundary)286boundary_points[curr_boundary_idx] = beacon_points[curr_beacon_idx];287288bool boundary_success = false; // true once the boundary has been successfully found289bool boundary_failure = false; // true if we fail to build the boundary290float start_angle = 0.0f; // starting angle used when searching for next boundary point, on each iteration this climbs but never climbs past PI * 2291while (!boundary_success && !boundary_failure) {292// look for next outer point293uint8_t next_idx;294float next_angle;295if (get_next_boundary_point(beacon_points, num_beacons, curr_beacon_idx, start_angle, next_idx, next_angle)) {296// add boundary point to boundary_sorted array297curr_boundary_idx++;298boundary_points[curr_boundary_idx] = beacon_points[next_idx];299curr_beacon_idx = next_idx;300start_angle = next_angle;301302// check if we have a complete boundary by looking for duplicate points within the boundary_sorted303uint8_t dup_idx = 0;304bool dup_found = false;305while (dup_idx < curr_boundary_idx && !dup_found) {306dup_found = (boundary_points[dup_idx] == boundary_points[curr_boundary_idx]);307if (!dup_found) {308dup_idx++;309}310}311// if duplicate is found, remove all boundary points before the duplicate because they are inner points312if (dup_found) {313// note that the closing/duplicate point is not314// included in the boundary points.315const uint8_t num_pts = curr_boundary_idx - dup_idx;316if (num_pts >= AP_BEACON_MINIMUM_FENCE_BEACONS) { // we consider three points to be a polygon317// success, copy boundary points to boundary array and convert meters to cm318for (uint8_t j = 0; j < num_pts; j++) {319boundary[j] = boundary_points[j+dup_idx] * 100.0f;320}321boundary_num_points = num_pts;322boundary_success = true;323} else {324// boundary has too few points325boundary_failure = true;326}327}328} else {329// failed to create boundary - give up!330boundary_failure = true;331}332}333334// clear boundary on failure335if (boundary_failure) {336boundary_num_points = 0;337}338}339340// find next boundary point from an array of boundary points given the current index into that array341// returns true if a next point can be found342// current_index should be an index into the boundary_pts array343// start_angle is an angle (in radians), the search will sweep clockwise from this angle344// the index of the next point is returned in the next_index argument345// the angle to the next point is returned in the next_angle argument346bool AP_Beacon::get_next_boundary_point(const Vector2f* boundary_pts, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t& next_index, float& next_angle)347{348// sanity check349if (boundary_pts == nullptr || current_index >= num_points) {350return false;351}352353// get current point354Vector2f curr_point = boundary_pts[current_index];355356// search through all points for next boundary point in a clockwise direction357float lowest_angle = M_PI_2;358float lowest_angle_relative = M_PI_2;359bool lowest_found = false;360uint8_t lowest_index = 0;361for (uint8_t i=0; i < num_points; i++) {362if (i != current_index) {363Vector2f vec = boundary_pts[i] - curr_point;364if (!vec.is_zero()) {365float angle = wrap_2PI(atan2f(vec.y, vec.x));366float angle_relative = wrap_2PI(angle - start_angle);367if ((angle_relative < lowest_angle_relative) || !lowest_found) {368lowest_angle = angle;369lowest_angle_relative = angle_relative;370lowest_index = i;371lowest_found = true;372}373}374}375}376377// return results378if (lowest_found) {379next_index = lowest_index;380next_angle = lowest_angle;381}382return lowest_found;383}384385// return fence boundary array386const Vector2f* AP_Beacon::get_boundary_points(uint16_t& num_points) const387{388if (!device_ready()) {389num_points = 0;390return nullptr;391}392393num_points = boundary_num_points;394return boundary;395}396397// check if the device is ready398bool AP_Beacon::device_ready(void) const399{400return ((_driver != nullptr) && (_type != Type::None));401}402403#if HAL_LOGGING_ENABLED404// Write beacon sensor (position) data405void AP_Beacon::log()406{407if (!enabled()) {408return;409}410// position411Vector3f pos;412float accuracy = 0.0f;413get_vehicle_position_ned(pos, accuracy);414415const struct log_Beacon pkt_beacon{416LOG_PACKET_HEADER_INIT(LOG_BEACON_MSG),417time_us : AP_HAL::micros64(),418health : (uint8_t)healthy(),419count : (uint8_t)count(),420dist0 : beacon_distance(0),421dist1 : beacon_distance(1),422dist2 : beacon_distance(2),423dist3 : beacon_distance(3),424posx : pos.x,425posy : pos.y,426posz : pos.z427};428AP::logger().WriteBlock(&pkt_beacon, sizeof(pkt_beacon));429}430#endif431432// singleton instance433AP_Beacon *AP_Beacon::_singleton;434435namespace AP {436437AP_Beacon *beacon()438{439return AP_Beacon::get_singleton();440}441442}443444#endif445446447