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_SITL.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_SITL.h"1617#if AP_BEACON_SITL_ENABLED1819#include <AP_HAL/AP_HAL.h>2021#include <stdio.h>2223extern const AP_HAL::HAL& hal;2425#define NUM_BEACONS 426/*27* Define a rectangular pattern of beacons with the pattern centroid located at the beacon origin as defined by the following params:28*29* BCN_ALT - Height above the WGS-84 geoid (m)30* BCN_LATITUDE - WGS-84 latitude (deg)31* BCN_LONGITUDE - WGS-84 longitude (deg)32*33* The spacing between beacons in the North/South and East/West directions is defined by the following parameters:34*/35#define BEACON_SPACING_NORTH 10.036#define BEACON_SPACING_EAST 20.03738// The centroid of the pattern can be moved using using the following parameters:39#define ORIGIN_OFFSET_NORTH 2.5 // shifts beacon pattern centroid North (m)40#define ORIGIN_OFFSET_EAST 5.0 // shifts beacon pattern centroid East (m)4142// constructor43AP_Beacon_SITL::AP_Beacon_SITL(AP_Beacon &frontend) :44AP_Beacon_Backend(frontend),45sitl(AP::sitl())46{47}4849// return true if sensor is basically healthy (we are receiving data)50bool AP_Beacon_SITL::healthy()51{52// healthy if we have parsed a message within the past 300ms53return ((AP_HAL::millis() - last_update_ms) < AP_BEACON_TIMEOUT_MS);54}5556// update the state of the sensor57void AP_Beacon_SITL::update(void)58{59uint32_t now = AP_HAL::millis();60if (now - last_update_ms < 10) {61return;62}6364uint8_t beacon_id = next_beacon;65next_beacon = (next_beacon+1) % NUM_BEACONS;6667// truth location of the flight vehicle68Location current_loc;69current_loc.lat = sitl->state.latitude * 1.0e7f;70current_loc.lng = sitl->state.longitude * 1.0e7f;71current_loc.alt = sitl->state.altitude * 1.0e2;7273// where the beacon system origin is located74Location beacon_origin;75beacon_origin.lat = get_beacon_origin_lat() * 1.0e7f;76beacon_origin.lng = get_beacon_origin_lon() * 1.0e7f;77beacon_origin.alt = get_beacon_origin_alt() * 1.0e2;7879// position of each beacon80Location beacon_loc = beacon_origin;81switch (beacon_id) {82case 0:83// NE corner84beacon_loc.offset(ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);85break;86case 1:87// SE corner88beacon_loc.offset(ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);89break;90case 2:91// SW corner92beacon_loc.offset(ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);93break;94case 3:95// NW corner96beacon_loc.offset(ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);97break;98}99100const Vector2f beac_diff = beacon_origin.get_distance_NE(beacon_loc);101const Vector2f veh_diff = beacon_origin.get_distance_NE(current_loc);102103Vector3f veh_pos3d(veh_diff.x, veh_diff.y, (beacon_origin.alt - current_loc.alt)*1.0e-2f);104Vector3f beac_pos3d(beac_diff.x, beac_diff.y, (beacon_loc.alt - beacon_origin.alt)*1.0e-2f);105Vector3f beac_veh_offset = veh_pos3d - beac_pos3d;106107set_beacon_position(beacon_id, beac_pos3d);108set_beacon_distance(beacon_id, beac_veh_offset.length());109set_vehicle_position(veh_pos3d, 0.5f);110last_update_ms = now;111}112113#endif // AP_BEACON_SITL_ENABLED114115116