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_Pozyx.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_Pozyx.h"1617#if AP_BEACON_POZYX_ENABLED1819#include <AP_HAL/AP_HAL.h>20#include <ctype.h>21#include <stdio.h>2223extern const AP_HAL::HAL& hal;2425// return true if sensor is basically healthy (we are receiving data)26bool AP_Beacon_Pozyx::healthy()27{28// healthy if we have parsed a message within the past 300ms29return ((AP_HAL::millis() - last_update_ms) < AP_BEACON_TIMEOUT_MS);30}3132// update the state of the sensor33void AP_Beacon_Pozyx::update(void)34{35if (uart == nullptr) {36return;37}3839// read any available characters40int16_t nbytes = uart->available();41while (nbytes-- > 0) {42char c = uart->read();4344switch (parse_state) {4546default:47case ParseState_WaitingForHeader:48if (c == AP_BEACON_POZYX_HEADER) {49parse_state = ParseState_WaitingForMsgId;50linebuf_len = 0;51}52break;5354case ParseState_WaitingForMsgId:55parse_msg_id = c;56switch (parse_msg_id) {57case AP_BEACON_POZYX_MSGID_BEACON_CONFIG:58case AP_BEACON_POZYX_MSGID_BEACON_DIST:59case AP_BEACON_POZYX_MSGID_POSITION:60parse_state = ParseState_WaitingForLen;61break;62default:63// invalid message id64parse_state = ParseState_WaitingForHeader;65break;66}67break;6869case ParseState_WaitingForLen:70parse_msg_len = c;71if (parse_msg_len > AP_BEACON_POZYX_MSG_LEN_MAX) {72// invalid message length73parse_state = ParseState_WaitingForHeader;74} else {75parse_state = ParseState_WaitingForContents;76}77break;7879case ParseState_WaitingForContents:80// add to buffer81linebuf[linebuf_len++] = c;82if ((linebuf_len == parse_msg_len) || (linebuf_len == sizeof(linebuf))) {83// process buffer84parse_buffer();85// reset state for next message86parse_state = ParseState_WaitingForHeader;87}88break;89}90}91}9293// parse buffer94void AP_Beacon_Pozyx::parse_buffer()95{96// check crc97uint8_t checksum = 0;98checksum ^= parse_msg_id;99checksum ^= parse_msg_len;100for (uint8_t i=0; i<linebuf_len; i++) {101checksum ^= linebuf[i];102}103// return if failed checksum check104if (checksum != 0) {105return;106}107108bool parsed = false;109switch (parse_msg_id) {110111case AP_BEACON_POZYX_MSGID_BEACON_CONFIG:112{113uint8_t beacon_id = linebuf[0];114//uint8_t beacon_count = linebuf[1];115int32_t beacon_x = (uint32_t)linebuf[5] << 24 | (uint32_t)linebuf[4] << 16 | (uint32_t)linebuf[3] << 8 | (uint32_t)linebuf[2];116int32_t beacon_y = (uint32_t)linebuf[9] << 24 | (uint32_t)linebuf[8] << 16 | (uint32_t)linebuf[7] << 8 | (uint32_t)linebuf[6];117int32_t beacon_z = (uint32_t)linebuf[13] << 24 | (uint32_t)linebuf[12] << 16 | (uint32_t)linebuf[11] << 8 | (uint32_t)linebuf[10];118Vector3f beacon_pos(beacon_x * 0.001f, beacon_y * 0.001f, -beacon_z * 0.001f);119if (beacon_pos.length() <= AP_BEACON_DISTANCE_MAX) {120set_beacon_position(beacon_id, beacon_pos);121parsed = true;122}123}124break;125126case AP_BEACON_POZYX_MSGID_BEACON_DIST:127{128uint8_t beacon_id = linebuf[0];129uint32_t beacon_distance = (uint32_t)linebuf[4] << 24 | (uint32_t)linebuf[3] << 16 | (uint32_t)linebuf[2] << 8 | (uint32_t)linebuf[1];130float beacon_dist = beacon_distance/1000.0f;131if (beacon_dist <= AP_BEACON_DISTANCE_MAX) {132set_beacon_distance(beacon_id, beacon_dist);133parsed = true;134}135}136break;137138case AP_BEACON_POZYX_MSGID_POSITION:139{140int32_t vehicle_x = (uint32_t)linebuf[3] << 24 | (uint32_t)linebuf[2] << 16 | (uint32_t)linebuf[1] << 8 | (uint32_t)linebuf[0];141int32_t vehicle_y = (uint32_t)linebuf[7] << 24 | (uint32_t)linebuf[6] << 16 | (uint32_t)linebuf[5] << 8 | (uint32_t)linebuf[4];142int32_t vehicle_z = (uint32_t)linebuf[11] << 24 | (uint32_t)linebuf[10] << 16 | (uint32_t)linebuf[9] << 8 | (uint32_t)linebuf[8];143int16_t position_error = (uint32_t)linebuf[13] << 8 | (uint32_t)linebuf[12];144Vector3f veh_pos(Vector3f(vehicle_x * 0.001f, vehicle_y * 0.001f, -vehicle_z * 0.001f));145if (veh_pos.length() <= AP_BEACON_DISTANCE_MAX) {146set_vehicle_position(veh_pos, position_error);147parsed = true;148}149}150break;151152default:153// unrecognised message id154break;155}156157// record success158if (parsed) {159last_update_ms = AP_HAL::millis();160}161}162163#endif // AP_BEACON_POZYX_ENABLED164165166