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_SBP.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_SBP.h"25#include <AP_Logger/AP_Logger.h>2627#if AP_GPS_SBP_ENABLED2829extern const AP_HAL::HAL& hal;3031#define SBP_DEBUGGING 132#define SBP_HW_LOGGING HAL_LOGGING_ENABLED3334#define SBP_TIMEOUT_HEATBEAT 400035#define SBP_TIMEOUT_PVT 5003637#if SBP_DEBUGGING38# define Debug(fmt, args ...) \39do { \40hal.console->printf("%s:%d: " fmt "\n", \41__FUNCTION__, __LINE__, \42## args); \43hal.scheduler->delay(1); \44} while(0)45#else46# define Debug(fmt, args ...)47#endif4849AP_GPS_SBP::AP_GPS_SBP(AP_GPS &_gps,50AP_GPS::Params &_params,51AP_GPS::GPS_State &_state,52AP_HAL::UARTDriver *_port) :53AP_GPS_Backend(_gps, _params, _state, _port)54{5556Debug("SBP Driver Initialized");5758parser_state.state = sbp_parser_state_t::WAITING;5960//Externally visible state61state.status = AP_GPS::NO_FIX;62state.last_gps_time_ms = last_heatbeat_received_ms = AP_HAL::millis();6364}6566// Process all bytes available from the stream67//68bool69AP_GPS_SBP::read(void)70{7172//Invariant: Calling this function processes *all* data current in the UART buffer.73//74//IMPORTANT NOTICE: This function is NOT CALLED for several seconds75// during arming. That should not cause the driver to die. Process *all* waiting messages7677_sbp_process();7879return _attempt_state_update();8081}8283void84AP_GPS_SBP::inject_data(const uint8_t *data, uint16_t len)85{8687if (port->txspace() > len) {88last_injected_data_ms = AP_HAL::millis();89port->write(data, len);90} else {91Debug("PIKSI: Not enough TXSPACE");92}9394}9596//This attempts to reads all SBP messages from the incoming port.97//Returns true if a new message was read, false if we failed to read a message.98void99AP_GPS_SBP::_sbp_process()100{101102while (port->available() > 0) {103uint8_t temp = port->read();104#if AP_GPS_DEBUG_LOGGING_ENABLED105log_data(&temp, 1);106#endif107uint16_t crc;108109110//This switch reads one character at a time,111//parsing it into buffers until a full message is dispatched112switch (parser_state.state) {113case sbp_parser_state_t::WAITING:114if (temp == SBP_PREAMBLE) {115parser_state.n_read = 0;116parser_state.state = sbp_parser_state_t::GET_TYPE;117}118break;119120case sbp_parser_state_t::GET_TYPE:121*((uint8_t*)&(parser_state.msg_type) + parser_state.n_read) = temp;122parser_state.n_read += 1;123if (parser_state.n_read >= 2) {124parser_state.n_read = 0;125parser_state.state = sbp_parser_state_t::GET_SENDER;126}127break;128129case sbp_parser_state_t::GET_SENDER:130*((uint8_t*)&(parser_state.sender_id) + parser_state.n_read) = temp;131parser_state.n_read += 1;132if (parser_state.n_read >= 2) {133parser_state.n_read = 0;134parser_state.state = sbp_parser_state_t::GET_LEN;135}136break;137138case sbp_parser_state_t::GET_LEN:139parser_state.msg_len = temp;140parser_state.n_read = 0;141parser_state.state = sbp_parser_state_t::GET_MSG;142break;143144case sbp_parser_state_t::GET_MSG:145*((uint8_t*)&(parser_state.msg_buff) + parser_state.n_read) = temp;146parser_state.n_read += 1;147if (parser_state.n_read >= parser_state.msg_len) {148parser_state.n_read = 0;149parser_state.state = sbp_parser_state_t::GET_CRC;150}151break;152153case sbp_parser_state_t::GET_CRC:154*((uint8_t*)&(parser_state.crc) + parser_state.n_read) = temp;155parser_state.n_read += 1;156if (parser_state.n_read >= 2) {157parser_state.state = sbp_parser_state_t::WAITING;158159crc = crc16_ccitt((uint8_t*)&(parser_state.msg_type), 2, 0);160crc = crc16_ccitt((uint8_t*)&(parser_state.sender_id), 2, crc);161crc = crc16_ccitt(&(parser_state.msg_len), 1, crc);162crc = crc16_ccitt(parser_state.msg_buff, parser_state.msg_len, crc);163if (parser_state.crc == crc) {164_sbp_process_message();165} else {166Debug("CRC Error Occurred!");167crc_error_counter += 1;168}169170parser_state.state = sbp_parser_state_t::WAITING;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_SBP::_sbp_process_message() {185switch (parser_state.msg_type) {186case SBP_HEARTBEAT_MSGTYPE:187last_heatbeat_received_ms = AP_HAL::millis();188break;189190case SBP_GPS_TIME_MSGTYPE:191memcpy(&last_gps_time, parser_state.msg_buff, sizeof(last_gps_time));192check_new_itow(last_gps_time.tow, parser_state.msg_len);193break;194195case SBP_VEL_NED_MSGTYPE:196memcpy(&last_vel_ned, parser_state.msg_buff, sizeof(last_vel_ned));197check_new_itow(last_vel_ned.tow, parser_state.msg_len);198break;199200case SBP_POS_LLH_MSGTYPE: {201struct sbp_pos_llh_t *pos_llh = (struct sbp_pos_llh_t*)parser_state.msg_buff;202check_new_itow(pos_llh->tow, parser_state.msg_len);203// Check if this is a single point or RTK solution204// flags = 0 -> single point205if (pos_llh->flags == 0) {206last_pos_llh_spp = *pos_llh;207} else if (pos_llh->flags == 1 || pos_llh->flags == 2) {208last_pos_llh_rtk = *pos_llh;209}210break;211}212213case SBP_DOPS_MSGTYPE:214memcpy(&last_dops, parser_state.msg_buff, sizeof(last_dops));215check_new_itow(last_dops.tow, parser_state.msg_len);216break;217218case SBP_TRACKING_STATE_MSGTYPE:219//INTENTIONALLY BLANK220//Currently unhandled, but logged after switch statement.221break;222223case SBP_IAR_STATE_MSGTYPE: {224sbp_iar_state_t *iar = (struct sbp_iar_state_t*)parser_state.msg_buff;225last_iar_num_hypotheses = iar->num_hypotheses;226break;227}228229default:230// log anyway if it's an unsupported message.231// The log mask will be used to adjust or suppress logging232break;233}234235#if SBP_HW_LOGGING236logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);237#endif238}239240bool241AP_GPS_SBP::_attempt_state_update()242{243244// If we currently have heartbeats245// - NO FIX246//247// If we have a full update available, save it248//249uint32_t now = AP_HAL::millis();250bool ret = false;251252if (now - last_heatbeat_received_ms > SBP_TIMEOUT_HEATBEAT) {253254state.status = AP_GPS::NO_FIX;255Debug("No Heartbeats from Piksi! Driver Ready to Die!");256257} else if (last_pos_llh_rtk.tow == last_vel_ned.tow258&& abs((int32_t) (last_gps_time.tow - last_vel_ned.tow)) < 10000259&& abs((int32_t) (last_dops.tow - last_vel_ned.tow)) < 60000260&& last_vel_ned.tow > last_full_update_tow) {261262// Use the RTK position263sbp_pos_llh_t *pos_llh = &last_pos_llh_rtk;264265// Update time state266state.time_week = last_gps_time.wn;267state.time_week_ms = last_vel_ned.tow;268269state.hdop = last_dops.hdop;270271// Update velocity state272state.velocity[0] = (float)(last_vel_ned.n * 1.0e-3);273state.velocity[1] = (float)(last_vel_ned.e * 1.0e-3);274state.velocity[2] = (float)(last_vel_ned.d * 1.0e-3);275state.have_vertical_velocity = true;276277velocity_to_speed_course(state);278279// Update position state280281state.location.lat = (int32_t) (pos_llh->lat * (double)1e7);282state.location.lng = (int32_t) (pos_llh->lon * (double)1e7);283state.location.alt = (int32_t) (pos_llh->height * 100);284state.num_sats = pos_llh->n_sats;285286if (pos_llh->flags == 0) {287state.status = AP_GPS::GPS_OK_FIX_3D;288} else if (pos_llh->flags == 2) {289state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;290} else if (pos_llh->flags == 1) {291state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;292}293294last_full_update_tow = last_vel_ned.tow;295last_full_update_cpu_ms = now;296state.rtk_iar_num_hypotheses = last_iar_num_hypotheses;297298#if SBP_HW_LOGGING299logging_log_full_update();300#endif301ret = true;302303} else if (now - last_full_update_cpu_ms > SBP_TIMEOUT_PVT) {304305//INVARIANT: If we currently have a fix, ONLY return true after a full update.306307state.status = AP_GPS::NO_FIX;308ret = true;309310} else {311312//No timeouts yet, no data yet, nothing has happened.313314}315316return ret;317318}319320321322bool323AP_GPS_SBP::_detect(struct SBP_detect_state &state, uint8_t data)324{325// This switch reads one character at a time, if we find something that326// looks like our preamble we'll try to read the full message length,327// calculating the CRC. If the CRC matches, we have an SBP GPS!328329switch (state.state) {330case SBP_detect_state::WAITING:331if (data == SBP_PREAMBLE) {332state.n_read = 0;333state.crc_so_far = 0;334state.state = SBP_detect_state::GET_TYPE;335}336break;337338case SBP_detect_state::GET_TYPE:339*((uint8_t*)&(state.msg_type) + state.n_read) = data;340state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);341state.n_read += 1;342if (state.n_read >= 2) {343state.n_read = 0;344state.state = SBP_detect_state::GET_SENDER;345}346break;347348case SBP_detect_state::GET_SENDER:349state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);350state.n_read += 1;351if (state.n_read >= 2) {352state.n_read = 0;353state.state = SBP_detect_state::GET_LEN;354}355break;356357case SBP_detect_state::GET_LEN:358state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);359state.msg_len = data;360state.n_read = 0;361state.state = SBP_detect_state::GET_MSG;362break;363364case SBP_detect_state::GET_MSG:365if (state.msg_type == SBP_HEARTBEAT_MSGTYPE && state.n_read < 4) {366*((uint8_t*)&(state.heartbeat_buff) + state.n_read) = data;367}368state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);369state.n_read += 1;370if (state.n_read >= state.msg_len) {371state.n_read = 0;372state.state = SBP_detect_state::GET_CRC;373}374break;375376case SBP_detect_state::GET_CRC:377*((uint8_t*)&(state.crc) + state.n_read) = data;378state.n_read += 1;379if (state.n_read >= 2) {380state.state = SBP_detect_state::WAITING;381if (state.crc == state.crc_so_far382&& state.msg_type == SBP_HEARTBEAT_MSGTYPE) {383struct sbp_heartbeat_t* heartbeat = ((struct sbp_heartbeat_t*)state.heartbeat_buff);384return heartbeat->protocol_major == 0;385}386return false;387}388break;389390default:391state.state = SBP_detect_state::WAITING;392break;393}394return false;395}396397#if SBP_HW_LOGGING398399void400AP_GPS_SBP::logging_log_full_update()401{402403if (!should_log()) {404return;405}406407struct log_SbpHealth pkt = {408LOG_PACKET_HEADER_INIT(LOG_MSG_SBPHEALTH),409time_us : AP_HAL::micros64(),410crc_error_counter : crc_error_counter,411last_injected_data_ms : last_injected_data_ms,412last_iar_num_hypotheses : last_iar_num_hypotheses,413};414415AP::logger().WriteBlock(&pkt, sizeof(pkt));416};417418void419AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type,420uint16_t sender_id,421uint8_t msg_len,422uint8_t *msg_buff) {423if (!should_log()) {424return;425}426427//MASK OUT MESSAGES WE DON'T WANT TO LOG428if (( ((uint16_t) gps._sbp_logmask) & msg_type) == 0) {429return;430}431432uint64_t time_us = AP_HAL::micros64();433uint8_t pages = 1;434435if (msg_len > 48) {436pages += (msg_len - 48) / 104 + 1;437}438439struct log_SbpRAWH pkt = {440LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWH),441time_us : time_us,442msg_type : msg_type,443sender_id : sender_id,444index : 1,445pages : pages,446msg_len : msg_len,447};448memcpy(pkt.data, msg_buff, MIN(msg_len, 48));449AP::logger().WriteBlock(&pkt, sizeof(pkt));450451for (uint8_t i = 0; i < pages - 1; i++) {452struct log_SbpRAWM pkt2 = {453LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWM),454time_us : time_us,455msg_type : msg_type,456sender_id : sender_id,457index : uint8_t(i + 2),458pages : pages,459msg_len : msg_len,460};461memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104));462AP::logger().WriteBlock(&pkt2, sizeof(pkt2));463}464};465466#endif // SBP_HW_LOGGING467#endif // AP_GPS_SBP_ENABLED468469470