Path: blob/master/libraries/AP_Beacon/AP_Beacon.cpp
9390 views
/*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 = Location{164int32_t(origin_lat * 1.0e7f),165int32_t(origin_lon * 1.0e7f),166int32_t(origin_alt * 100),167Location::AltFrame::ABSOLUTE168};169170return true;171}172173// return position in NED from position estimate system's origin in meters174bool AP_Beacon::get_vehicle_position_ned(Vector3f &position, float& accuracy_estimate) const175{176if (!device_ready()) {177return false;178}179180// check for timeout181if (AP_HAL::millis() - veh_pos_update_ms > AP_BEACON_TIMEOUT_MS) {182return false;183}184185// return position186position = veh_pos_ned;187accuracy_estimate = veh_pos_accuracy;188return true;189}190191// return the number of beacons192uint8_t AP_Beacon::count() const193{194if (!device_ready()) {195return 0;196}197return num_beacons;198}199200// return all beacon data201bool AP_Beacon::get_beacon_data(uint8_t beacon_instance, struct BeaconState& state) const202{203if (!device_ready() || beacon_instance >= num_beacons) {204return false;205}206state = beacon_state[beacon_instance];207return true;208}209210// return individual beacon's id211uint8_t AP_Beacon::beacon_id(uint8_t beacon_instance) const212{213if (beacon_instance >= num_beacons) {214return 0;215}216return beacon_state[beacon_instance].id;217}218219// return beacon health220bool AP_Beacon::beacon_healthy(uint8_t beacon_instance) const221{222if (beacon_instance >= num_beacons) {223return false;224}225return beacon_state[beacon_instance].healthy;226}227228// return distance to beacon in meters229float AP_Beacon::beacon_distance(uint8_t beacon_instance) const230{231if ( beacon_instance >= num_beacons || !beacon_state[beacon_instance].healthy) {232return 0.0f;233}234return beacon_state[beacon_instance].distance;235}236237// return beacon position in meters238Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const239{240if (!device_ready() || beacon_instance >= num_beacons) {241Vector3f temp = {};242return temp;243}244return beacon_state[beacon_instance].position;245}246247// return last update time from beacon in milliseconds248uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const249{250if (_type == Type::None || beacon_instance >= num_beacons) {251return 0;252}253return beacon_state[beacon_instance].distance_update_ms;254}255256// create fence boundary points257void AP_Beacon::update_boundary_points()258{259// we need three beacons at least to create boundary fence.260// update boundary fence if number of beacons changes261if (!device_ready() || num_beacons < AP_BEACON_MINIMUM_FENCE_BEACONS || boundary_num_beacons == num_beacons) {262return;263}264265// record number of beacons so we do not repeat calculations266boundary_num_beacons = num_beacons;267268// accumulate beacon points269Vector2f beacon_points[AP_BEACON_MAX_BEACONS];270for (uint8_t index = 0; index < num_beacons; index++) {271const Vector3f& point_3d = beacon_position(index);272beacon_points[index].x = point_3d.x;273beacon_points[index].y = point_3d.y;274}275276// create polygon around boundary points using the following algorithm277// set the "current point" as the first boundary point278// 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 angle279// check if point is already in boundary280// - no: add to boundary, move current point to this new point and repeat the above281// - yes: we've completed the bounding box, delete any boundary points found earlier than the duplicate282283Vector2f boundary_points[AP_BEACON_MAX_BEACONS+1]; // array of boundary points284uint8_t curr_boundary_idx = 0; // index into boundary_sorted index. always points to the highest filled in element of the array285uint8_t curr_beacon_idx = 0; // index into beacon_point array. point indexed is same point as curr_boundary_idx's286287// 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)288boundary_points[curr_boundary_idx] = beacon_points[curr_beacon_idx];289290bool boundary_success = false; // true once the boundary has been successfully found291bool boundary_failure = false; // true if we fail to build the boundary292float start_angle = 0.0f; // starting angle used when searching for next boundary point, on each iteration this climbs but never climbs past PI * 2293while (!boundary_success && !boundary_failure) {294// look for next outer point295uint8_t next_idx;296float next_angle;297if (get_next_boundary_point(beacon_points, num_beacons, curr_beacon_idx, start_angle, next_idx, next_angle)) {298// add boundary point to boundary_sorted array299curr_boundary_idx++;300boundary_points[curr_boundary_idx] = beacon_points[next_idx];301curr_beacon_idx = next_idx;302start_angle = next_angle;303304// check if we have a complete boundary by looking for duplicate points within the boundary_sorted305uint8_t dup_idx = 0;306bool dup_found = false;307while (dup_idx < curr_boundary_idx && !dup_found) {308dup_found = (boundary_points[dup_idx] == boundary_points[curr_boundary_idx]);309if (!dup_found) {310dup_idx++;311}312}313// if duplicate is found, remove all boundary points before the duplicate because they are inner points314if (dup_found) {315// note that the closing/duplicate point is not316// included in the boundary points.317const uint8_t num_pts = curr_boundary_idx - dup_idx;318if (num_pts >= AP_BEACON_MINIMUM_FENCE_BEACONS) { // we consider three points to be a polygon319// success, copy boundary points to boundary array and convert meters to cm320for (uint8_t j = 0; j < num_pts; j++) {321boundary[j] = boundary_points[j+dup_idx] * 100.0f;322}323boundary_num_points = num_pts;324boundary_success = true;325} else {326// boundary has too few points327boundary_failure = true;328}329}330} else {331// failed to create boundary - give up!332boundary_failure = true;333}334}335336// clear boundary on failure337if (boundary_failure) {338boundary_num_points = 0;339}340}341342// find next boundary point from an array of boundary points given the current index into that array343// returns true if a next point can be found344// current_index should be an index into the boundary_pts array345// start_angle is an angle (in radians), the search will sweep clockwise from this angle346// the index of the next point is returned in the next_index argument347// the angle to the next point is returned in the next_angle argument348bool 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)349{350// sanity check351if (boundary_pts == nullptr || current_index >= num_points) {352return false;353}354355// get current point356Vector2f curr_point = boundary_pts[current_index];357358// search through all points for next boundary point in a clockwise direction359float lowest_angle = M_PI_2;360float lowest_angle_relative = M_PI_2;361bool lowest_found = false;362uint8_t lowest_index = 0;363for (uint8_t i=0; i < num_points; i++) {364if (i != current_index) {365Vector2f vec = boundary_pts[i] - curr_point;366if (!vec.is_zero()) {367float angle = wrap_2PI(atan2f(vec.y, vec.x));368float angle_relative = wrap_2PI(angle - start_angle);369if ((angle_relative < lowest_angle_relative) || !lowest_found) {370lowest_angle = angle;371lowest_angle_relative = angle_relative;372lowest_index = i;373lowest_found = true;374}375}376}377}378379// return results380if (lowest_found) {381next_index = lowest_index;382next_angle = lowest_angle;383}384return lowest_found;385}386387// return fence boundary array388const Vector2f* AP_Beacon::get_boundary_points(uint16_t& num_points) const389{390if (!device_ready()) {391num_points = 0;392return nullptr;393}394395num_points = boundary_num_points;396return boundary;397}398399// check if the device is ready400bool AP_Beacon::device_ready(void) const401{402return ((_driver != nullptr) && (_type != Type::None));403}404405#if HAL_LOGGING_ENABLED406// Write beacon sensor (position) data407void AP_Beacon::log()408{409if (!enabled()) {410return;411}412// position413Vector3f pos;414float accuracy = 0.0f;415get_vehicle_position_ned(pos, accuracy);416417const struct log_Beacon pkt_beacon{418LOG_PACKET_HEADER_INIT(LOG_BEACON_MSG),419time_us : AP_HAL::micros64(),420health : (uint8_t)healthy(),421count : (uint8_t)count(),422dist0 : beacon_distance(0),423dist1 : beacon_distance(1),424dist2 : beacon_distance(2),425dist3 : beacon_distance(3),426posx : pos.x,427posy : pos.y,428posz : pos.z429};430AP::logger().WriteBlock(&pkt_beacon, sizeof(pkt_beacon));431}432#endif433434// singleton instance435AP_Beacon *AP_Beacon::_singleton;436437namespace AP {438439AP_Beacon *beacon()440{441return AP_Beacon::get_singleton();442}443444}445446#endif447448449