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_Nooploop.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_Nooploop.h"1617#if AP_BEACON_NOOPLOOP_ENABLED1819#include <AP_HAL/AP_HAL.h>20#include <GCS_MAVLink/GCS.h>21#include <ctype.h>22#include <stdio.h>2324#define NOOPLOOP_INVALID_VAL -8388000 // indicates data unavailable or invalid25#define NOOPLOOP_SF0_SZ 128 // setting_frame0 packet size2627#define NOOPLOOP_HEADER 0x55 // message header28#define NOOPLOOP_FUNCTION_MARK_NODE_FRAME2 429#define NOOPLOOP_NODE_FRAME2_FRAMELEN_MAX 4096 // frames should be less than 4k bytes30#define NOOPLOOP_NODE_FRAME2_SYSTIME 6 // start of 4 bytes holding system time in ms31#define NOOPLOOP_NODE_FRAME2_PRECISION_X 10 // start of 1 byte holding precision in m*100 in x axis32#define NOOPLOOP_NODE_FRAME2_PRECISION_Y 11 // start of 1 byte holding precision in m*100 in y axis33#define NOOPLOOP_NODE_FRAME2_PRECISION_Z 12 // start of 1 byte holding precision in m*100 in y axis34#define NOOPLOOP_NODE_FRAME2_POSX 13 // start of 3 bytes holding x position in m*100035#define NOOPLOOP_NODE_FRAME2_POSY 16 // start of 3 bytes holding y position in m*100036#define NOOPLOOP_NODE_FRAME2_POSZ 19 // start of 3 bytes holding z position in m*100037#define NOOPLOOP_NODE_FRAME2_VALID_NODES 11838#define NOOPLOOP_NODE_FRAME2_NODE_BLOCK 1193940#define NOOPLOOP_HEADER2 0x54 // message header41#define NOOPLOOP_FUNCTION_MARK_SETTING_FRAME0 042#define NOOPLOOP_SETTING_FRAME0_A0 37434445extern const AP_HAL::HAL& hal;4647// return true if sensor is basically healthy (we are receiving data)48bool AP_Beacon_Nooploop::healthy()49{50// healthy if we have parsed a message within the past 300ms51return ((AP_HAL::millis() - _last_update_ms) < AP_BEACON_TIMEOUT_MS);52}5354// update the state of the sensor55void AP_Beacon_Nooploop::update(void)56{57// return immediately if not serial port58if (uart == nullptr) {59return;60}6162// check uart for any incoming messages63uint32_t nbytes = MIN(uart->available(), 1024U);64while (nbytes-- > 0) {65int16_t b = uart->read();66if (b >= 0 ) {67MsgType type = parse_byte((uint8_t)b);68if (type == MsgType::NODE_FRAME2) {69if (_anchor_pos_avail) {70parse_node_frame2();71} else if (AP_HAL::millis() - _last_request_setting_ms > 2000) {72_last_request_setting_ms = AP_HAL::millis();73request_setting();74}75} else if (type == MsgType::SETTING_FRAME0) {76parse_setting_frame0();77}78}79}80}8182void AP_Beacon_Nooploop::request_setting()83{84//send setting_frame0 to tag, tag will fill anchor position and ack85uart->write((uint8_t)0x54);86uart->write((uint8_t)0);87uart->write((uint8_t)1);88for (uint8_t i = 0; i < 124; i++) {89uart->write((uint8_t)0); //manual states filled with any char, but in fact only 0 works90}91uart->write((uint8_t)0x55);92}9394// process one byte received on serial port95// message is stored in _msgbuf96AP_Beacon_Nooploop::MsgType AP_Beacon_Nooploop::parse_byte(uint8_t b)97{98// process byte depending upon current state99switch (_state) {100101case ParseState::HEADER:102if (b == NOOPLOOP_HEADER) {103_msgbuf[0] = b;104_msg_len = 1;105_crc_expected = b;106_state = ParseState::H55_FUNCTION_MARK;107} else if (b == NOOPLOOP_HEADER2) {108_msgbuf[0] = b;109_msg_len = 1;110_crc_expected = b;111_state = ParseState::H54_FUNCTION_MARK;112}113break;114115case ParseState::H55_FUNCTION_MARK:116if (b == NOOPLOOP_FUNCTION_MARK_NODE_FRAME2) {117_msgbuf[1] = b;118_msg_len++;119_crc_expected += b;120_state = ParseState::LEN_L;121} else {122_state = ParseState::HEADER;123}124break;125126case ParseState::H54_FUNCTION_MARK:127if (b == NOOPLOOP_FUNCTION_MARK_SETTING_FRAME0) {128_msgbuf[1] = b;129_msg_len++;130_crc_expected += b;131_state = ParseState::SF0_PAYLOAD;132} else {133_state = ParseState::HEADER;134}135break;136137case ParseState::LEN_L:138_msgbuf[2] = b;139_msg_len++;140_crc_expected += b;141_state = ParseState::LEN_H;142break;143144case ParseState::LEN_H:145// extract and sanity check frame length146_frame_len = UINT16_VALUE(b, _msgbuf[2]);147if (_frame_len > NOOPLOOP_NODE_FRAME2_FRAMELEN_MAX) {148_state = ParseState::HEADER;149} else {150_msgbuf[3] = b;151_msg_len++;152_crc_expected += b;153_state = ParseState::NF2_PAYLOAD;154}155break;156157case ParseState::NF2_PAYLOAD:158// add byte to buffer if there is room159if (_msg_len < NOOPLOOP_MSG_BUF_MAX) {160_msgbuf[_msg_len] = b;161}162_msg_len++;163if (_msg_len >= _frame_len) {164_state = ParseState::HEADER;165// check crc166if (b == _crc_expected) {167return MsgType::NODE_FRAME2;168}169} else {170_crc_expected += b;171}172break;173174case ParseState::SF0_PAYLOAD:175// add byte to buffer if there is room176if (_msg_len < NOOPLOOP_MSG_BUF_MAX) {177_msgbuf[_msg_len] = b;178}179_msg_len++;180if (_msg_len >= NOOPLOOP_SF0_SZ) {181_state = ParseState::HEADER;182// check crc183if (b == _crc_expected) {184return MsgType::SETTING_FRAME0;185}186} else {187_crc_expected += b;188}189break;190}191192return MsgType::INVALID;193}194195void AP_Beacon_Nooploop::parse_node_frame2()196{197// a message has been received198_last_update_ms = AP_HAL::millis();199200// estimated precision for x,y position in meters201const float precision_x = _msgbuf[NOOPLOOP_NODE_FRAME2_PRECISION_X] * 0.01;202const float precision_y = _msgbuf[NOOPLOOP_NODE_FRAME2_PRECISION_Y] * 0.01;203//EKF's estimate goes very bad if the error value sent into the EKF is unrealistically low. ensure it's never less than a reasonable value204const float pos_err = MAX(0.1f, sqrtf(sq(precision_x)+sq(precision_y)));205206// x,y,z position in m*1000 in ENU frame207const int32_t pos_x = ((int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSX+2] << 24 | (int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSX+1] << 16 | (int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSX] << 8) >> 8;208const int32_t pos_y = ((int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSY+2] << 24 | (int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSY+1] << 16 | (int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSY] << 8) >> 8;209const int32_t pos_z = ((int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSZ+2] << 24 | (int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSZ+1] << 16 | (int32_t)_msgbuf[NOOPLOOP_NODE_FRAME2_POSZ] << 8) >> 8;210211// position scaled to meters and changed to NED212const Vector3f pos_m {pos_y * 0.001f, pos_x * 0.001f, -pos_z * 0.001f};213214set_vehicle_position(pos_m, pos_err);215216const uint8_t valid_nodes = _msgbuf[NOOPLOOP_NODE_FRAME2_VALID_NODES];217for (uint8_t i = 0; i < valid_nodes; i++) {218uint16_t offset = NOOPLOOP_NODE_FRAME2_NODE_BLOCK + i * 13;219uint8_t id = _msgbuf[offset+1]; //nooploop id starts from 0, increments clockwise, 0 -> 1 define Y axis.220const int32_t dist = ((int32_t)_msgbuf[offset+2+2] << 24 | (int32_t)_msgbuf[offset+2+1] << 16 | (int32_t)_msgbuf[offset+2] << 8) >> 8;221set_beacon_distance(id, dist * 0.001f);222}223}224225void AP_Beacon_Nooploop::parse_setting_frame0()226{227for (uint8_t i = 0; i < 4; i++) {228uint16_t offset = NOOPLOOP_SETTING_FRAME0_A0 + i * 9;229230// x,y,z position in m*1000 in ENU frame231const int32_t pos_x = ((int32_t)_msgbuf[offset+2] << 24 | (int32_t)_msgbuf[offset+1] << 16 | (int32_t)_msgbuf[offset] << 8) >> 8;232if (pos_x == NOOPLOOP_INVALID_VAL) { //anchor position not available233return;234}235offset+=3;236const int32_t pos_y = ((int32_t)_msgbuf[offset+2] << 24 | (int32_t)_msgbuf[offset+1] << 16 | (int32_t)_msgbuf[offset] << 8) >> 8;237if (pos_y == NOOPLOOP_INVALID_VAL) {238return;239}240offset+=3;241const int32_t pos_z = ((int32_t)_msgbuf[offset+2] << 24 | (int32_t)_msgbuf[offset+1] << 16 | (int32_t)_msgbuf[offset] << 8) >> 8;242if (pos_z == NOOPLOOP_INVALID_VAL) {243return;244}245246// position scaled to meters and changed to NED247const Vector3f pos_m {pos_y * 0.001f, pos_x * 0.001f, -pos_z * 0.001f};248249set_beacon_position(i, pos_m);250}251_anchor_pos_avail = true;252}253254#endif // AP_BEACON_NOOPLOOP_ENABLED255256257