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_GPS/AP_GPS_SBP2.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//16// Swift Navigation SBP GPS driver for ArduPilot.17// Code by Niels Joubert18//19// Swift Binary Protocol format: http://docs.swift-nav.com/20//212223#include "AP_GPS.h"24#include "AP_GPS_SBP2.h"25#include <AP_Logger/AP_Logger.h>26#include <GCS_MAVLink/GCS_MAVLink.h>27#include <GCS_MAVLink/GCS.h>2829#if AP_GPS_SBP2_ENABLED3031extern const AP_HAL::HAL& hal;3233#define SBP_DEBUGGING 034#define SBP_INFOREPORTING 13536//INVARIANT: We expect SBP to give us a heartbeat in less than 2 seconds.37// This is more lax than the default Piksi settings,38// and we assume the user hasn't reconfigured their Piksi to longer heartbeat intervals39#define SBP_TIMEOUT_HEARTBEAT 20004041#if SBP_DEBUGGING42# define Debug(fmt, args ...) \43do { \44hal.console->printf("%s:%d: " fmt "\n", \45__FUNCTION__, __LINE__, \46## args); \47hal.scheduler->delay(1); \48} while(0)49#else50# define Debug(fmt, args ...)51#endif5253#if SBP_INFOREPORTING54# define Info(fmt, args ...) \55do { \56GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt "\n", ## args); \57} while(0)58#else59# define Info(fmt, args ...)60#endif616263AP_GPS_SBP2::AP_GPS_SBP2(AP_GPS &_gps,64AP_GPS::Params &_params,65AP_GPS::GPS_State &_state,66AP_HAL::UARTDriver *_port) :67AP_GPS_Backend(_gps, _params, _state, _port)68{69Debug("SBP Driver Initialized");70parser_state.state = sbp_parser_state_t::WAITING;71}7273// Process all bytes available from the stream74//75bool76AP_GPS_SBP2::read(void)77{78//Invariant: Calling this function processes *all* data current in the UART buffer.79//80//IMPORTANT NOTICE: This function is NOT CALLED for several seconds81// during arming. That should not cause the driver to die. Process *all* waiting messages8283_sbp_process();84return _attempt_state_update();85}8687void88AP_GPS_SBP2::inject_data(const uint8_t *data, uint16_t len)89{90if (port->txspace() > len) {91last_injected_data_ms = AP_HAL::millis();92port->write(data, len);93} else {94Debug("PIKSI: Not enough TXSPACE");95}96}9798//This attempts to reads all SBP messages from the incoming port.99//Returns true if a new message was read, false if we failed to read a message.100void101AP_GPS_SBP2::_sbp_process()102{103uint32_t nleft = port->available();104while (nleft > 0) {105nleft--;106uint8_t temp = port->read();107#if AP_GPS_DEBUG_LOGGING_ENABLED108log_data(&temp, 1);109#endif110uint16_t crc;111112//This switch reads one character at a time,113//parsing it into buffers until a full message is dispatched114switch (parser_state.state) {115case sbp_parser_state_t::WAITING:116if (temp == SBP_PREAMBLE) {117parser_state.n_read = 0;118parser_state.state = sbp_parser_state_t::GET_TYPE;119}120break;121122case sbp_parser_state_t::GET_TYPE:123*((uint8_t*)&(parser_state.msg_type) + parser_state.n_read) = temp;124parser_state.n_read += 1;125if (parser_state.n_read >= 2) {126parser_state.n_read = 0;127parser_state.state = sbp_parser_state_t::GET_SENDER;128}129break;130131case sbp_parser_state_t::GET_SENDER:132*((uint8_t*)&(parser_state.sender_id) + parser_state.n_read) = temp;133parser_state.n_read += 1;134if (parser_state.n_read >= 2) {135parser_state.n_read = 0;136parser_state.state = sbp_parser_state_t::GET_LEN;137}138break;139140case sbp_parser_state_t::GET_LEN:141parser_state.msg_len = temp;142parser_state.n_read = 0;143parser_state.state = sbp_parser_state_t::GET_MSG;144break;145146case sbp_parser_state_t::GET_MSG:147*((uint8_t*)&(parser_state.msg_buff) + parser_state.n_read) = temp;148parser_state.n_read += 1;149if (parser_state.n_read >= parser_state.msg_len) {150parser_state.n_read = 0;151parser_state.state = sbp_parser_state_t::GET_CRC;152}153break;154155case sbp_parser_state_t::GET_CRC:156*((uint8_t*)&(parser_state.crc) + parser_state.n_read) = temp;157parser_state.n_read += 1;158if (parser_state.n_read >= 2) {159parser_state.state = sbp_parser_state_t::WAITING;160161crc = crc16_ccitt((uint8_t*)&(parser_state.msg_type), 2, 0);162crc = crc16_ccitt((uint8_t*)&(parser_state.sender_id), 2, crc);163crc = crc16_ccitt(&(parser_state.msg_len), 1, crc);164crc = crc16_ccitt(parser_state.msg_buff, parser_state.msg_len, crc);165if (parser_state.crc == crc) {166_sbp_process_message();167} else {168Debug("CRC Error Occurred!");169crc_error_counter += 1;170}171}172break;173174default:175parser_state.state = sbp_parser_state_t::WAITING;176break;177}178}179}180181182//INVARIANT: A fully received message with correct CRC is currently in parser_state183void184AP_GPS_SBP2::_sbp_process_message() {185//Here, we copy messages into local structs.186switch (parser_state.msg_type) {187case SBP_HEARTBEAT_MSGTYPE:188memcpy(&last_heartbeat, parser_state.msg_buff, sizeof(struct sbp_heartbeat_t));189last_heartbeat_received_ms = AP_HAL::millis();190break;191192case SBP_GPS_TIME_MSGTYPE:193memcpy(&last_gps_time, parser_state.msg_buff, sizeof(struct sbp_gps_time_t));194check_new_itow(last_gps_time.tow, parser_state.msg_len);195break;196197case SBP_VEL_NED_MSGTYPE:198memcpy(&last_vel_ned, parser_state.msg_buff, sizeof(struct sbp_vel_ned_t));199check_new_itow(last_vel_ned.tow, parser_state.msg_len);200break;201202case SBP_POS_LLH_MSGTYPE:203memcpy(&last_pos_llh, parser_state.msg_buff, sizeof(struct sbp_pos_llh_t));204check_new_itow(last_pos_llh.tow, parser_state.msg_len);205break;206207case SBP_DOPS_MSGTYPE:208memcpy(&last_dops, parser_state.msg_buff, sizeof(struct sbp_dops_t));209check_new_itow(last_dops.tow, parser_state.msg_len);210break;211212case SBP_EXT_EVENT_MSGTYPE:213memcpy(&last_event, parser_state.msg_buff, sizeof(struct sbp_ext_event_t));214check_new_itow(last_event.tow, parser_state.msg_len);215#if HAL_LOGGING_ENABLED216logging_ext_event();217#endif218break;219220default:221break;222}223224#if HAL_LOGGING_ENABLED225// send all messages we receive to log, even if it's an unsupported message,226// so we can do additional post-processing from logs.227// The log mask will be used to adjust or suppress logging228logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);229#endif230}231232int32_t233AP_GPS_SBP2::distMod(int32_t tow1_ms, int32_t tow2_ms, int32_t mod) {234return MIN(abs(tow1_ms - tow2_ms), mod - abs(tow1_ms - tow2_ms));235}236237bool238AP_GPS_SBP2::_attempt_state_update()239{240if (last_heartbeat_received_ms == 0)241return false;242243uint32_t now = AP_HAL::millis();244245if (now - last_heartbeat_received_ms > SBP_TIMEOUT_HEARTBEAT) {246247state.status = AP_GPS::NO_FIX;248Info("No Heartbeats from Piksi! Status to NO_FIX.");249return false;250251} else if (last_heartbeat.protocol_major != 2) {252253state.status = AP_GPS::NO_FIX;254Info("Received a heartbeat from non-SBPv2 device. Current driver only supports SBPv2. Status to NO_FIX.");255return false;256257} else if (last_heartbeat.nap_error == 1 ||258last_heartbeat.io_error == 1 ||259last_heartbeat.sys_error == 1) {260261state.status = AP_GPS::NO_FIX;262263Info("Piksi reported an error. Status to NO_FIX.");264Debug(" ext_antenna: %d", last_heartbeat.ext_antenna);265Debug(" res2: %d", last_heartbeat.res2);266Debug(" protocol_major: %d", last_heartbeat.protocol_major);267Debug(" protocol_minor: %d", last_heartbeat.protocol_minor);268Debug(" res: %d", last_heartbeat.res);269Debug(" nap_error: %d", last_heartbeat.nap_error);270Debug(" io_error: %d", last_heartbeat.io_error);271Debug(" sys_error: %d", last_heartbeat.sys_error);272273return false;274275} else if (last_pos_llh.tow == last_vel_ned.tow276&& (distMod(last_gps_time.tow, last_vel_ned.tow, AP_MSEC_PER_WEEK) < 10000)277&& (distMod(last_dops.tow, last_vel_ned.tow, AP_MSEC_PER_WEEK) < 60000)278&& (last_vel_ned.tow > last_full_update_tow || (last_gps_time.wn > last_full_update_wn && last_vel_ned.tow < last_full_update_tow))) {279280//We have an aligned VEL and LLH, and a recent DOPS and TIME.281282//283// Check Flags for Valid Messages284//285if (last_gps_time.flags.time_src == 0 ||286last_vel_ned.flags.vel_mode == 0 ||287last_pos_llh.flags.fix_mode == 0 ||288last_dops.flags.fix_mode == 0) {289290Debug("Message Marked as Invalid. NO FIX! Flags: {GPS_TIME: %d, VEL_NED: %d, POS_LLH: %d, DOPS: %d}",291last_gps_time.flags.time_src,292last_vel_ned.flags.vel_mode,293last_pos_llh.flags.fix_mode,294last_dops.flags.fix_mode);295296state.status = AP_GPS::NO_FIX;297return false;298}299300//301// Update external time and accuracy state302//303state.time_week = last_gps_time.wn;304state.time_week_ms = last_vel_ned.tow;305state.hdop = last_dops.hdop;306state.vdop = last_dops.vdop;307state.last_gps_time_ms = now;308309//310// Update velocity state311//312state.velocity[0] = (float)(last_vel_ned.n * 1.0e-3);313state.velocity[1] = (float)(last_vel_ned.e * 1.0e-3);314state.velocity[2] = (float)(last_vel_ned.d * 1.0e-3);315316velocity_to_speed_course(state);317318state.speed_accuracy = safe_sqrt(319powf((float)last_vel_ned.h_accuracy * 1.0e-3f, 2) +320powf((float)last_vel_ned.v_accuracy * 1.0e-3f, 2));321state.horizontal_accuracy = (float) last_pos_llh.h_accuracy * 1.0e-3f;322state.vertical_accuracy = (float) last_pos_llh.v_accuracy * 1.0e-3f;323324//325// Set flags appropriately326//327state.have_vertical_velocity = true;328state.have_speed_accuracy = !is_zero(state.speed_accuracy);329state.have_horizontal_accuracy = !is_zero(state.horizontal_accuracy);330state.have_vertical_accuracy = !is_zero(state.vertical_accuracy);331332//333// Update position state334//335state.location.lat = (int32_t) (last_pos_llh.lat * (double)1e7);336state.location.lng = (int32_t) (last_pos_llh.lon * (double)1e7);337state.location.alt = (int32_t) (last_pos_llh.height * 100);338state.num_sats = last_pos_llh.n_sats;339340switch (last_pos_llh.flags.fix_mode) {341case 1:342state.status = AP_GPS::GPS_OK_FIX_3D;343break;344case 2:345state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;346break;347case 3:348state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;349break;350case 4:351state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;352break;353case 6:354state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;355break;356default:357state.status = AP_GPS::NO_FIX;358break;359}360361//362// Update Internal Timing363//364last_full_update_tow = last_vel_ned.tow;365last_full_update_wn = last_gps_time.wn;366367return true;368}369return false;370}371372373374bool375AP_GPS_SBP2::_detect(struct SBP2_detect_state &state, uint8_t data)376{377// This switch reads one character at a time, if we find something that378// looks like our preamble we'll try to read the full message length,379// calculating the CRC. If the CRC matches, we have an SBP GPS!380switch (state.state) {381case SBP2_detect_state::WAITING:382if (data == SBP_PREAMBLE) {383state.n_read = 0;384state.crc_so_far = 0;385state.state = SBP2_detect_state::GET_TYPE;386}387break;388389case SBP2_detect_state::GET_TYPE:390*((uint8_t*)&(state.msg_type) + state.n_read) = data;391state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);392state.n_read += 1;393if (state.n_read >= 2) {394state.n_read = 0;395state.state = SBP2_detect_state::GET_SENDER;396}397break;398399case SBP2_detect_state::GET_SENDER:400state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);401state.n_read += 1;402if (state.n_read >= 2) {403state.n_read = 0;404state.state = SBP2_detect_state::GET_LEN;405}406break;407408case SBP2_detect_state::GET_LEN:409state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);410state.msg_len = data;411state.n_read = 0;412state.state = SBP2_detect_state::GET_MSG;413break;414415case SBP2_detect_state::GET_MSG:416if (state.msg_type == SBP_HEARTBEAT_MSGTYPE && state.n_read < 4) {417*((uint8_t*)&(state.heartbeat_buff) + state.n_read) = data;418}419state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);420state.n_read += 1;421if (state.n_read >= state.msg_len) {422state.n_read = 0;423state.state = SBP2_detect_state::GET_CRC;424}425break;426427case SBP2_detect_state::GET_CRC:428*((uint8_t*)&(state.crc) + state.n_read) = data;429state.n_read += 1;430if (state.n_read >= 2) {431state.state = SBP2_detect_state::WAITING;432if (state.crc == state.crc_so_far433&& state.msg_type == SBP_HEARTBEAT_MSGTYPE) {434struct sbp_heartbeat_t* heartbeat = ((struct sbp_heartbeat_t*)state.heartbeat_buff);435return heartbeat->protocol_major == 2;436}437return false;438}439break;440441default:442state.state = SBP2_detect_state::WAITING;443break;444}445return false;446}447448#if HAL_LOGGING_ENABLED449void450AP_GPS_SBP2::logging_log_full_update()451{452if (!should_log()) {453return;454}455456//TODO: Expand with heartbeat info.457//TODO: Get rid of IAR NUM HYPO458459struct log_SbpHealth pkt = {460LOG_PACKET_HEADER_INIT(LOG_MSG_SBPHEALTH),461time_us : AP_HAL::micros64(),462crc_error_counter : crc_error_counter,463last_injected_data_ms : last_injected_data_ms,464last_iar_num_hypotheses : 0,465};466AP::logger().WriteBlock(&pkt, sizeof(pkt));467};468469void470AP_GPS_SBP2::logging_log_raw_sbp(uint16_t msg_type,471uint16_t sender_id,472uint8_t msg_len,473uint8_t *msg_buff) {474if (!should_log()) {475return;476}477478//MASK OUT MESSAGES WE DON'T WANT TO LOG479if (( ((uint16_t) gps._sbp_logmask) & msg_type) == 0) {480return;481}482483uint64_t time_us = AP_HAL::micros64();484uint8_t pages = 1;485486if (msg_len > 48) {487pages += (msg_len - 48) / 104 + 1;488}489490struct log_SbpRAWH pkt = {491LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWH),492time_us : time_us,493msg_type : msg_type,494sender_id : sender_id,495index : 1,496pages : pages,497msg_len : msg_len,498};499memcpy(pkt.data, msg_buff, MIN(msg_len, 48));500AP::logger().WriteBlock(&pkt, sizeof(pkt));501502for (uint8_t i = 0; i < pages - 1; i++) {503struct log_SbpRAWM pkt2 = {504LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWM),505time_us : time_us,506msg_type : msg_type,507sender_id : sender_id,508index : uint8_t(i + 2),509pages : pages,510msg_len : msg_len,511};512memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104));513AP::logger().WriteBlock(&pkt2, sizeof(pkt2));514}515};516517void518AP_GPS_SBP2::logging_ext_event() {519if (!should_log()) {520return;521}522523struct log_SbpEvent pkt = {524LOG_PACKET_HEADER_INIT(LOG_MSG_SBPEVENT),525time_us : AP_HAL::micros64(),526wn : last_event.wn,527tow : last_event.tow,528ns_residual : last_event.ns_residual,529level : last_event.flags.level,530quality : last_event.flags.quality,531};532AP::logger().WriteBlock(&pkt, sizeof(pkt));533};534#endif // HAL_LOGGING_ENABLED535#endif //AP_GPS_SBP2_ENABLED536537538