2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2010-09-06 19:31:18 -03:00
|
|
|
//
|
2014-03-28 16:52:27 -03:00
|
|
|
// u-blox GPS driver for ArduPilot
|
|
|
|
// Origin code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
|
2016-05-12 14:02:29 -03:00
|
|
|
// Substantially rewritten for new GPS driver structure by Andrew Tridgell
|
2010-09-06 19:31:18 -03:00
|
|
|
//
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_GPS.h"
|
2014-03-28 16:52:27 -03:00
|
|
|
#include "AP_GPS_UBLOX.h"
|
2016-02-02 03:58:33 -04:00
|
|
|
#include <AP_HAL/Util.h>
|
2019-01-18 00:23:42 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2016-02-02 03:58:33 -04:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2010-09-06 17:16:50 -03:00
|
|
|
|
2015-11-28 05:38:13 -04:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
|
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
|
2016-02-02 03:58:33 -04:00
|
|
|
#define UBLOX_SPEED_CHANGE 1
|
2015-04-09 12:10:16 -03:00
|
|
|
#else
|
2016-02-02 03:58:33 -04:00
|
|
|
#define UBLOX_SPEED_CHANGE 0
|
2015-04-09 12:10:16 -03:00
|
|
|
#endif
|
|
|
|
|
2015-04-01 08:49:34 -03:00
|
|
|
|
2012-06-08 03:39:12 -03:00
|
|
|
#define UBLOX_DEBUGGING 0
|
2013-10-02 03:10:22 -03:00
|
|
|
#define UBLOX_FAKE_3DLOCK 0
|
2018-06-22 02:25:27 -03:00
|
|
|
#define CONFIGURE_PPS_PIN 0
|
2012-06-08 03:39:12 -03:00
|
|
|
|
2013-01-06 00:10:04 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2012-06-15 02:53:14 -03:00
|
|
|
|
2019-05-26 22:34:13 -03:00
|
|
|
#ifdef HAL_NO_GCS
|
|
|
|
#define GCS_SEND_TEXT(severity, format, args...)
|
|
|
|
#else
|
|
|
|
#define GCS_SEND_TEXT(severity, format, args...) gcs().send_text(severity, format, ##args)
|
|
|
|
#endif
|
|
|
|
|
2012-06-15 02:53:14 -03:00
|
|
|
#if UBLOX_DEBUGGING
|
2013-03-20 01:42:07 -03:00
|
|
|
# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
|
2012-06-08 03:39:12 -03:00
|
|
|
#else
|
2012-08-21 23:19:52 -03:00
|
|
|
# define Debug(fmt, args ...)
|
2012-06-08 03:39:12 -03:00
|
|
|
#endif
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
|
|
|
AP_GPS_Backend(_gps, _state, _port),
|
2017-01-12 02:19:35 -04:00
|
|
|
_next_message(STEP_PVT),
|
2016-02-02 03:58:33 -04:00
|
|
|
_ublox_port(255),
|
|
|
|
_unconfigured_messages(CONFIG_ALL),
|
2017-05-24 14:42:03 -03:00
|
|
|
_hardware_generation(UBLOX_UNKNOWN_HARDWARE_GENERATION),
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix(AP_GPS::NO_FIX),
|
2018-05-16 04:26:53 -03:00
|
|
|
noReceivedHdop(true)
|
2010-09-06 17:16:50 -03:00
|
|
|
{
|
2014-03-31 06:52:07 -03:00
|
|
|
// stop any config strings that are pending
|
2016-10-30 02:24:21 -03:00
|
|
|
gps.send_blob_start(state.instance, nullptr, 0);
|
2014-03-31 06:52:07 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
// start the process of updating the GPS rates
|
|
|
|
_request_next_config();
|
2018-06-22 02:25:27 -03:00
|
|
|
|
|
|
|
#if CONFIGURE_PPS_PIN
|
|
|
|
_unconfigured_messages |= CONFIG_TP5;
|
|
|
|
#endif
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
|
|
|
|
2013-10-01 23:32:32 -03:00
|
|
|
void
|
2016-02-02 03:58:33 -04:00
|
|
|
AP_GPS_UBLOX::_request_next_config(void)
|
2013-10-01 23:32:32 -03:00
|
|
|
{
|
2016-02-02 03:58:33 -04:00
|
|
|
// don't request config if we shouldn't configure the GPS
|
2017-06-11 04:58:45 -03:00
|
|
|
if (gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) {
|
2016-02-02 03:58:33 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Ensure there is enough space for the largest possible outgoing message
|
2014-03-28 16:52:27 -03:00
|
|
|
if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_nav_rate)+2)) {
|
2013-10-01 23:32:32 -03:00
|
|
|
// not enough space - do it next time
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-07-01 01:51:56 -03:00
|
|
|
if (_unconfigured_messages == CONFIG_RATE_SOL && havePvtMsg) {
|
|
|
|
/*
|
|
|
|
we don't need SOL if we have PVT and TIMEGPS. This is needed
|
|
|
|
as F9P doesn't support the SOL message
|
|
|
|
*/
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_SOL;
|
|
|
|
}
|
|
|
|
|
|
|
|
Debug("Unconfigured messages: 0x%x Current message: %u\n", (unsigned)_unconfigured_messages, (unsigned)_next_message);
|
2013-10-02 03:10:22 -03:00
|
|
|
|
2019-01-04 00:40:41 -04:00
|
|
|
// check AP_GPS_UBLOX.h for the enum that controls the order.
|
|
|
|
// This switch statement isn't maintained against the enum in order to reduce code churn
|
2016-02-02 03:58:33 -04:00
|
|
|
switch (_next_message++) {
|
2017-01-12 02:19:35 -04:00
|
|
|
case STEP_PVT:
|
|
|
|
if(!_request_message_rate(CLASS_NAV, MSG_PVT)) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_next_message--;
|
|
|
|
}
|
2013-10-01 23:32:32 -03:00
|
|
|
break;
|
2019-03-30 01:21:11 -03:00
|
|
|
case STEP_TIMEGPS:
|
|
|
|
if(!_request_message_rate(CLASS_NAV, MSG_TIMEGPS)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_PORT:
|
|
|
|
_request_port();
|
2013-10-01 23:32:32 -03:00
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_POLL_SVINFO:
|
|
|
|
// not required once we know what generation we are on
|
2017-05-24 14:42:03 -03:00
|
|
|
if(_hardware_generation == UBLOX_UNKNOWN_HARDWARE_GENERATION) {
|
2017-02-15 19:20:21 -04:00
|
|
|
if (!_send_message(CLASS_NAV, MSG_NAV_SVINFO, 0, 0)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
2013-10-01 23:32:32 -03:00
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_POLL_SBAS:
|
2016-11-20 23:57:19 -04:00
|
|
|
if (gps._sbas_mode != 2) {
|
|
|
|
_send_message(CLASS_CFG, MSG_CFG_SBAS, nullptr, 0);
|
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_SBAS;
|
|
|
|
}
|
2016-10-16 21:56:34 -03:00
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_POLL_NAV:
|
2017-02-15 19:20:21 -04:00
|
|
|
if (!_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, nullptr, 0)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
2015-07-14 02:09:43 -03:00
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_POLL_GNSS:
|
2017-02-15 19:20:21 -04:00
|
|
|
if (!_send_message(CLASS_CFG, MSG_CFG_GNSS, nullptr, 0)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
2014-03-23 22:02:37 -03:00
|
|
|
break;
|
2018-06-22 02:25:27 -03:00
|
|
|
case STEP_POLL_TP5:
|
|
|
|
#if CONFIGURE_PPS_PIN
|
|
|
|
if (!_send_message(CLASS_CFG, MSG_CFG_TP5, nullptr, 0)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_NAV_RATE:
|
2017-02-15 19:20:21 -04:00
|
|
|
if (!_send_message(CLASS_CFG, MSG_CFG_RATE, nullptr, 0)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
2015-07-14 02:26:51 -03:00
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_POSLLH:
|
2017-01-12 02:19:35 -04:00
|
|
|
if(!_request_message_rate(CLASS_NAV, MSG_POSLLH)) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case STEP_STATUS:
|
2017-01-12 02:19:35 -04:00
|
|
|
if(!_request_message_rate(CLASS_NAV, MSG_STATUS)) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case STEP_SOL:
|
|
|
|
if(!_request_message_rate(CLASS_NAV, MSG_SOL)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case STEP_VELNED:
|
2017-01-12 02:19:35 -04:00
|
|
|
if(!_request_message_rate(CLASS_NAV, MSG_VELNED)) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case STEP_DOP:
|
|
|
|
if(! _request_message_rate(CLASS_NAV, MSG_DOP)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case STEP_MON_HW:
|
|
|
|
if(!_request_message_rate(CLASS_MON, MSG_MON_HW)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case STEP_MON_HW2:
|
|
|
|
if(!_request_message_rate(CLASS_MON, MSG_MON_HW2)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case STEP_RAW:
|
2015-07-14 02:26:51 -03:00
|
|
|
#if UBLOX_RXM_RAW_LOGGING
|
2016-02-02 03:58:33 -04:00
|
|
|
if(gps._raw_data == 0) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_RAW;
|
|
|
|
} else if(!_request_message_rate(CLASS_RXM, MSG_RXM_RAW)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
#else
|
2016-02-12 19:07:48 -04:00
|
|
|
_unconfigured_messages & = ~CONFIG_RATE_RAW;
|
2015-07-14 02:26:51 -03:00
|
|
|
#endif
|
2015-04-01 08:49:34 -03:00
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_RAWX:
|
2015-07-14 02:26:51 -03:00
|
|
|
#if UBLOX_RXM_RAW_LOGGING
|
2016-02-02 03:58:33 -04:00
|
|
|
if(gps._raw_data == 0) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_RAW;
|
|
|
|
} else if(!_request_message_rate(CLASS_RXM, MSG_RXM_RAWX)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
#else
|
2016-02-12 19:07:48 -04:00
|
|
|
_unconfigured_messages & = ~CONFIG_RATE_RAW;
|
2015-05-04 05:18:34 -03:00
|
|
|
#endif
|
2015-07-14 02:26:51 -03:00
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case STEP_VERSION:
|
2016-02-12 18:23:18 -04:00
|
|
|
if(!_have_version && !hal.util->get_soft_armed()) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_request_version();
|
2016-02-12 18:23:18 -04:00
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_VERSION;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
2019-11-05 23:43:41 -04:00
|
|
|
break;
|
|
|
|
case STEP_TMODE:
|
|
|
|
if (_hardware_generation >= UBLOX_F9) {
|
|
|
|
if (!_configure_valget(ConfigKey::TMODE_MODE)) {
|
|
|
|
_next_message--;
|
|
|
|
}
|
|
|
|
}
|
2015-07-14 02:26:51 -03:00
|
|
|
break;
|
2014-03-23 22:02:37 -03:00
|
|
|
default:
|
2016-02-02 03:58:33 -04:00
|
|
|
// this case should never be reached, do a full reset if it is hit
|
2017-01-12 02:19:35 -04:00
|
|
|
_next_message = STEP_PVT;
|
2014-03-23 22:02:37 -03:00
|
|
|
break;
|
2013-10-01 23:32:32 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
void
|
|
|
|
AP_GPS_UBLOX::_verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) {
|
2017-01-12 02:19:35 -04:00
|
|
|
uint8_t desired_rate;
|
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
switch(msg_class) {
|
|
|
|
case CLASS_NAV:
|
|
|
|
switch(msg_id) {
|
|
|
|
case MSG_POSLLH:
|
2017-01-12 02:19:35 -04:00
|
|
|
desired_rate = havePvtMsg ? 0 : RATE_POSLLH;
|
|
|
|
if(rate == desired_rate) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_POSLLH;
|
|
|
|
} else {
|
2017-01-12 02:19:35 -04:00
|
|
|
_configure_message_rate(msg_class, msg_id, desired_rate);
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages |= CONFIG_RATE_POSLLH;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case MSG_STATUS:
|
2017-01-12 02:19:35 -04:00
|
|
|
desired_rate = havePvtMsg ? 0 : RATE_STATUS;
|
|
|
|
if(rate == desired_rate) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_STATUS;
|
|
|
|
} else {
|
2017-01-12 02:19:35 -04:00
|
|
|
_configure_message_rate(msg_class, msg_id, desired_rate);
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages |= CONFIG_RATE_STATUS;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case MSG_SOL:
|
2019-03-30 01:21:11 -03:00
|
|
|
desired_rate = havePvtMsg ? 0 : RATE_SOL;
|
|
|
|
if(rate == desired_rate) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_SOL;
|
|
|
|
} else {
|
2019-03-30 01:21:11 -03:00
|
|
|
_configure_message_rate(msg_class, msg_id, desired_rate);
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages |= CONFIG_RATE_SOL;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
2016-07-30 20:38:43 -03:00
|
|
|
case MSG_PVT:
|
|
|
|
if(rate == RATE_PVT) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_PVT;
|
|
|
|
} else {
|
|
|
|
_configure_message_rate(msg_class, msg_id, RATE_PVT);
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_PVT;
|
|
|
|
_cfg_needs_save = true;
|
|
|
|
}
|
|
|
|
break;
|
2019-03-30 01:21:11 -03:00
|
|
|
case MSG_TIMEGPS:
|
|
|
|
if(rate == RATE_TIMEGPS) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_TIMEGPS;
|
|
|
|
} else {
|
|
|
|
_configure_message_rate(msg_class, msg_id, RATE_TIMEGPS);
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_TIMEGPS;
|
|
|
|
_cfg_needs_save = true;
|
|
|
|
}
|
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
case MSG_VELNED:
|
2017-01-12 02:19:35 -04:00
|
|
|
desired_rate = havePvtMsg ? 0 : RATE_VELNED;
|
|
|
|
if(rate == desired_rate) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_VELNED;
|
|
|
|
} else {
|
2017-01-12 02:19:35 -04:00
|
|
|
_configure_message_rate(msg_class, msg_id, desired_rate);
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages |= CONFIG_RATE_VELNED;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case MSG_DOP:
|
|
|
|
if(rate == RATE_DOP) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_DOP;
|
|
|
|
} else {
|
|
|
|
_configure_message_rate(msg_class, msg_id, RATE_DOP);
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_DOP;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case CLASS_MON:
|
|
|
|
switch(msg_id) {
|
|
|
|
case MSG_MON_HW:
|
|
|
|
if(rate == RATE_HW) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_MON_HW;
|
|
|
|
} else {
|
|
|
|
_configure_message_rate(msg_class, msg_id, RATE_HW);
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_MON_HW;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case MSG_MON_HW2:
|
|
|
|
if(rate == RATE_HW2) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_MON_HW2;
|
|
|
|
} else {
|
|
|
|
_configure_message_rate(msg_class, msg_id, RATE_HW2);
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_MON_HW2;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
#if UBLOX_RXM_RAW_LOGGING
|
|
|
|
case CLASS_RXM:
|
|
|
|
switch(msg_id) {
|
|
|
|
case MSG_RXM_RAW:
|
|
|
|
if(rate == gps._raw_data) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_RAW;
|
|
|
|
} else {
|
|
|
|
_configure_message_rate(msg_class, msg_id, gps._raw_data);
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_RAW;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case MSG_RXM_RAWX:
|
|
|
|
if(rate == gps._raw_data) {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_RAW;
|
|
|
|
} else {
|
|
|
|
_configure_message_rate(msg_class, msg_id, gps._raw_data);
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_RAW;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
#endif // UBLOX_RXM_RAW_LOGGING
|
|
|
|
}
|
|
|
|
}
|
2013-10-01 23:32:32 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
// Requests the ublox driver to identify what port we are using to communicate
|
|
|
|
void
|
|
|
|
AP_GPS_UBLOX::_request_port(void)
|
|
|
|
{
|
|
|
|
if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+2)) {
|
|
|
|
// not enough space - do it next time
|
|
|
|
return;
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
_send_message(CLASS_CFG, MSG_CFG_PRT, nullptr, 0);
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
2019-01-04 00:40:41 -04:00
|
|
|
|
|
|
|
// Ensure there is enough space for the largest possible outgoing message
|
2010-09-06 19:31:18 -03:00
|
|
|
// Process bytes available from the stream
|
|
|
|
//
|
|
|
|
// The stream is assumed to contain only messages we recognise. If it
|
|
|
|
// contains other messages, and those messages contain the preamble
|
|
|
|
// bytes, it is possible for this code to fail to synchronise to the
|
|
|
|
// stream immediately. Without buffering the entire message and
|
|
|
|
// re-processing it from the top, this is unavoidable. The parser
|
|
|
|
// attempts to avoid this when possible.
|
|
|
|
//
|
2010-12-24 02:35:09 -04:00
|
|
|
bool
|
|
|
|
AP_GPS_UBLOX::read(void)
|
2010-09-06 17:16:50 -03:00
|
|
|
{
|
2012-08-21 23:19:52 -03:00
|
|
|
uint8_t data;
|
|
|
|
int16_t numc;
|
|
|
|
bool parsed = false;
|
2015-11-19 23:10:22 -04:00
|
|
|
uint32_t millis_now = AP_HAL::millis();
|
2011-10-28 15:52:50 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
// walk through the gps configuration at 1 message per second
|
|
|
|
if (millis_now - _last_config_time >= _delay_time) {
|
|
|
|
_request_next_config();
|
|
|
|
_last_config_time = millis_now;
|
|
|
|
if (_unconfigured_messages) { // send the updates faster until fully configured
|
2017-02-15 19:20:21 -04:00
|
|
|
if (!havePvtMsg && (_unconfigured_messages & CONFIG_REQUIRED_INITIAL)) {
|
|
|
|
_delay_time = 300;
|
|
|
|
} else {
|
|
|
|
_delay_time = 750;
|
|
|
|
}
|
2016-02-02 03:58:33 -04:00
|
|
|
} else {
|
2016-10-16 21:56:34 -03:00
|
|
|
_delay_time = 2000;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-02-12 16:32:08 -04:00
|
|
|
if(!_unconfigured_messages && gps._save_config && !_cfg_saved &&
|
2016-02-02 03:58:33 -04:00
|
|
|
_num_cfg_save_tries < 5 && (millis_now - _last_cfg_sent_time) > 5000 &&
|
|
|
|
!hal.util->get_soft_armed()) {
|
|
|
|
//save the configuration sent until now
|
2016-02-12 16:32:08 -04:00
|
|
|
if (gps._save_config == 1 ||
|
|
|
|
(gps._save_config == 2 && _cfg_needs_save)) {
|
|
|
|
_save_cfg();
|
|
|
|
}
|
2013-10-01 23:32:32 -03:00
|
|
|
}
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
numc = port->available();
|
2012-08-21 23:19:52 -03:00
|
|
|
for (int16_t i = 0; i < numc; i++) { // Process bytes received
|
2011-10-28 15:52:50 -03:00
|
|
|
|
|
|
|
// read the next byte
|
2014-03-28 16:52:27 -03:00
|
|
|
data = port->read();
|
2011-10-28 15:52:50 -03:00
|
|
|
|
2013-01-05 01:32:42 -04:00
|
|
|
reset:
|
2011-10-28 15:52:50 -03:00
|
|
|
switch(_step) {
|
|
|
|
|
2012-08-21 23:19:52 -03:00
|
|
|
// Message preamble detection
|
|
|
|
//
|
|
|
|
// If we fail to match any of the expected bytes, we reset
|
|
|
|
// the state machine and re-consider the failed byte as
|
|
|
|
// the first byte of the preamble. This improves our
|
|
|
|
// chances of recovering from a mismatch and makes it less
|
|
|
|
// likely that we will be fooled by the preamble appearing
|
|
|
|
// as data in some other message.
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 1:
|
|
|
|
if (PREAMBLE2 == data) {
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
_step = 0;
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("reset %u", __LINE__);
|
2017-08-22 14:28:10 -03:00
|
|
|
FALLTHROUGH;
|
2011-10-28 15:52:50 -03:00
|
|
|
case 0:
|
|
|
|
if(PREAMBLE1 == data)
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:52 -03:00
|
|
|
// Message header processing
|
|
|
|
//
|
|
|
|
// We sniff the class and message ID to decide whether we
|
|
|
|
// are going to gather the message bytes or just discard
|
|
|
|
// them.
|
|
|
|
//
|
|
|
|
// We always collect the length so that we can avoid being
|
|
|
|
// fooled by preamble bytes in messages.
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 2:
|
|
|
|
_step++;
|
2012-08-21 23:19:52 -03:00
|
|
|
_class = data;
|
2019-01-04 00:40:41 -04:00
|
|
|
_ck_b = _ck_a = data; // reset the checksum accumulators
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
_step++;
|
2012-08-21 23:19:52 -03:00
|
|
|
_ck_b += (_ck_a += data); // checksum byte
|
2011-10-28 15:52:50 -03:00
|
|
|
_msg_id = data;
|
|
|
|
break;
|
|
|
|
case 4:
|
|
|
|
_step++;
|
2012-08-21 23:19:52 -03:00
|
|
|
_ck_b += (_ck_a += data); // checksum byte
|
2019-01-04 00:40:41 -04:00
|
|
|
_payload_length = data; // payload length low byte
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
case 5:
|
|
|
|
_step++;
|
2012-08-21 23:19:52 -03:00
|
|
|
_ck_b += (_ck_a += data); // checksum byte
|
2012-06-10 03:34:13 -03:00
|
|
|
|
|
|
|
_payload_length += (uint16_t)(data<<8);
|
2015-07-20 00:12:58 -03:00
|
|
|
if (_payload_length > sizeof(_buffer)) {
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("large payload %u", (unsigned)_payload_length);
|
2015-07-20 00:12:58 -03:00
|
|
|
// assume any payload bigger then what we know about is noise
|
2012-08-21 23:19:52 -03:00
|
|
|
_payload_length = 0;
|
|
|
|
_step = 0;
|
2013-01-05 01:32:42 -04:00
|
|
|
goto reset;
|
2012-08-21 23:19:52 -03:00
|
|
|
}
|
2019-01-04 00:40:41 -04:00
|
|
|
_payload_counter = 0; // prepare to receive payload
|
2019-09-26 08:14:41 -03:00
|
|
|
if (_payload_length == 0) {
|
|
|
|
// bypass payload and go straight to checksum
|
|
|
|
_step++;
|
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:52 -03:00
|
|
|
// Receive message data
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 6:
|
2012-08-21 23:19:52 -03:00
|
|
|
_ck_b += (_ck_a += data); // checksum byte
|
|
|
|
if (_payload_counter < sizeof(_buffer)) {
|
2016-06-06 10:49:46 -03:00
|
|
|
_buffer[_payload_counter] = data;
|
2012-08-21 23:19:52 -03:00
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
if (++_payload_counter == _payload_length)
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:52 -03:00
|
|
|
// Checksum and message processing
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 7:
|
|
|
|
_step++;
|
2012-06-08 03:39:12 -03:00
|
|
|
if (_ck_a != data) {
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("bad cka %x should be %x", data, _ck_a);
|
2013-01-05 01:32:42 -04:00
|
|
|
_step = 0;
|
|
|
|
goto reset;
|
2012-08-21 23:19:52 -03:00
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
case 8:
|
|
|
|
_step = 0;
|
2012-06-08 03:39:12 -03:00
|
|
|
if (_ck_b != data) {
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("bad ckb %x should be %x", data, _ck_b);
|
|
|
|
break; // bad checksum
|
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
|
2012-08-21 23:19:52 -03:00
|
|
|
if (_parse_gps()) {
|
|
|
|
parsed = true;
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
2015-07-14 02:23:10 -03:00
|
|
|
break;
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
return parsed;
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
|
|
|
|
2010-09-06 19:31:18 -03:00
|
|
|
// Private Methods /////////////////////////////////////////////////////////////
|
2014-03-23 22:02:37 -03:00
|
|
|
void AP_GPS_UBLOX::log_mon_hw(void)
|
|
|
|
{
|
2019-05-26 22:34:13 -03:00
|
|
|
#ifndef HAL_NO_LOGGING
|
2019-02-11 04:19:08 -04:00
|
|
|
if (!should_log()) {
|
2014-03-23 22:02:37 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
struct log_Ubx1 pkt = {
|
2015-09-09 09:08:58 -03:00
|
|
|
LOG_PACKET_HEADER_INIT(_ubx_msg_log_index(LOG_GPS_UBX1_MSG)),
|
2015-11-19 23:10:22 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2014-03-28 16:52:27 -03:00
|
|
|
instance : state.instance,
|
2014-04-02 20:55:05 -03:00
|
|
|
noisePerMS : _buffer.mon_hw_60.noisePerMS,
|
|
|
|
jamInd : _buffer.mon_hw_60.jamInd,
|
2014-10-28 16:50:51 -03:00
|
|
|
aPower : _buffer.mon_hw_60.aPower,
|
|
|
|
agcCnt : _buffer.mon_hw_60.agcCnt,
|
2017-10-04 15:08:38 -03:00
|
|
|
config : _unconfigured_messages,
|
2014-03-23 22:02:37 -03:00
|
|
|
};
|
2014-04-02 20:55:05 -03:00
|
|
|
if (_payload_length == 68) {
|
|
|
|
pkt.noisePerMS = _buffer.mon_hw_68.noisePerMS;
|
|
|
|
pkt.jamInd = _buffer.mon_hw_68.jamInd;
|
|
|
|
pkt.aPower = _buffer.mon_hw_68.aPower;
|
2014-10-28 16:50:51 -03:00
|
|
|
pkt.agcCnt = _buffer.mon_hw_68.agcCnt;
|
2014-04-02 20:55:05 -03:00
|
|
|
}
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
2019-05-26 22:34:13 -03:00
|
|
|
#endif
|
2014-03-23 22:02:37 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void AP_GPS_UBLOX::log_mon_hw2(void)
|
|
|
|
{
|
2019-05-26 22:34:13 -03:00
|
|
|
#ifndef HAL_NO_LOGGING
|
2019-02-11 04:19:08 -04:00
|
|
|
if (!should_log()) {
|
2014-03-23 22:02:37 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct log_Ubx2 pkt = {
|
2015-09-09 09:08:58 -03:00
|
|
|
LOG_PACKET_HEADER_INIT(_ubx_msg_log_index(LOG_GPS_UBX2_MSG)),
|
2015-11-19 23:10:22 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2014-03-28 16:52:27 -03:00
|
|
|
instance : state.instance,
|
2014-03-23 22:02:37 -03:00
|
|
|
ofsI : _buffer.mon_hw2.ofsI,
|
|
|
|
magI : _buffer.mon_hw2.magI,
|
|
|
|
ofsQ : _buffer.mon_hw2.ofsQ,
|
|
|
|
magQ : _buffer.mon_hw2.magQ,
|
|
|
|
};
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
2019-05-26 22:34:13 -03:00
|
|
|
#endif
|
2014-03-23 22:02:37 -03:00
|
|
|
}
|
2014-10-28 16:44:07 -03:00
|
|
|
|
2015-05-04 05:18:34 -03:00
|
|
|
#if UBLOX_RXM_RAW_LOGGING
|
|
|
|
void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw)
|
|
|
|
{
|
2019-05-26 22:34:13 -03:00
|
|
|
#ifndef HAL_NO_LOGGING
|
2019-02-11 04:19:08 -04:00
|
|
|
if (!should_log()) {
|
2015-05-04 05:18:34 -03:00
|
|
|
return;
|
|
|
|
}
|
2017-06-27 05:12:45 -03:00
|
|
|
|
2015-11-19 23:10:22 -04:00
|
|
|
uint64_t now = AP_HAL::micros64();
|
2015-05-04 05:18:34 -03:00
|
|
|
for (uint8_t i=0; i<raw.numSV; i++) {
|
|
|
|
struct log_GPS_RAW pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_GPS_RAW_MSG),
|
2015-04-30 00:49:03 -03:00
|
|
|
time_us : now,
|
2015-05-04 05:18:34 -03:00
|
|
|
iTOW : raw.iTOW,
|
|
|
|
week : raw.week,
|
|
|
|
numSV : raw.numSV,
|
|
|
|
sv : raw.svinfo[i].sv,
|
|
|
|
cpMes : raw.svinfo[i].cpMes,
|
|
|
|
prMes : raw.svinfo[i].prMes,
|
|
|
|
doMes : raw.svinfo[i].doMes,
|
|
|
|
mesQI : raw.svinfo[i].mesQI,
|
|
|
|
cno : raw.svinfo[i].cno,
|
|
|
|
lli : raw.svinfo[i].lli
|
|
|
|
};
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
2015-05-04 05:18:34 -03:00
|
|
|
}
|
2019-05-26 22:34:13 -03:00
|
|
|
#endif
|
2015-05-04 05:18:34 -03:00
|
|
|
}
|
2015-06-29 19:04:35 -03:00
|
|
|
|
|
|
|
void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw)
|
|
|
|
{
|
2019-05-26 22:34:13 -03:00
|
|
|
#ifndef HAL_NO_LOGGING
|
2019-02-11 04:19:08 -04:00
|
|
|
if (!should_log()) {
|
2015-06-29 19:04:35 -03:00
|
|
|
return;
|
|
|
|
}
|
2017-06-27 05:12:45 -03:00
|
|
|
|
2015-11-19 23:10:22 -04:00
|
|
|
uint64_t now = AP_HAL::micros64();
|
2015-06-29 19:04:35 -03:00
|
|
|
|
|
|
|
struct log_GPS_RAWH header = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_GPS_RAWH_MSG),
|
|
|
|
time_us : now,
|
|
|
|
rcvTow : raw.rcvTow,
|
|
|
|
week : raw.week,
|
|
|
|
leapS : raw.leapS,
|
|
|
|
numMeas : raw.numMeas,
|
|
|
|
recStat : raw.recStat
|
|
|
|
};
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().WriteBlock(&header, sizeof(header));
|
2015-06-29 19:04:35 -03:00
|
|
|
|
|
|
|
for (uint8_t i=0; i<raw.numMeas; i++) {
|
|
|
|
struct log_GPS_RAWS pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_GPS_RAWS_MSG),
|
|
|
|
time_us : now,
|
|
|
|
prMes : raw.svinfo[i].prMes,
|
|
|
|
cpMes : raw.svinfo[i].cpMes,
|
|
|
|
doMes : raw.svinfo[i].doMes,
|
|
|
|
gnssId : raw.svinfo[i].gnssId,
|
|
|
|
svId : raw.svinfo[i].svId,
|
|
|
|
freqId : raw.svinfo[i].freqId,
|
|
|
|
locktime : raw.svinfo[i].locktime,
|
|
|
|
cno : raw.svinfo[i].cno,
|
|
|
|
prStdev : raw.svinfo[i].prStdev,
|
|
|
|
cpStdev : raw.svinfo[i].cpStdev,
|
|
|
|
doStdev : raw.svinfo[i].doStdev,
|
|
|
|
trkStat : raw.svinfo[i].trkStat
|
|
|
|
};
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
2015-06-29 19:04:35 -03:00
|
|
|
}
|
2019-05-26 22:34:13 -03:00
|
|
|
#endif
|
2015-06-29 19:04:35 -03:00
|
|
|
}
|
2015-05-04 05:18:34 -03:00
|
|
|
#endif // UBLOX_RXM_RAW_LOGGING
|
|
|
|
|
2014-03-23 22:02:37 -03:00
|
|
|
void AP_GPS_UBLOX::unexpected_message(void)
|
|
|
|
{
|
|
|
|
Debug("Unexpected message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
|
|
|
|
if (++_disable_counter == 0) {
|
|
|
|
// disable future sends of this message id, but
|
|
|
|
// only do this every 256 messages, as some
|
|
|
|
// message types can't be disabled and we don't
|
|
|
|
// want to get into an ack war
|
|
|
|
Debug("Disabling message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
|
|
|
|
_configure_message_rate(_class, _msg_id, 0);
|
|
|
|
}
|
|
|
|
}
|
2010-09-06 19:31:18 -03:00
|
|
|
|
2010-12-24 02:35:09 -04:00
|
|
|
bool
|
2010-09-06 19:31:18 -03:00
|
|
|
AP_GPS_UBLOX::_parse_gps(void)
|
2010-09-06 17:16:50 -03:00
|
|
|
{
|
2012-08-21 23:19:52 -03:00
|
|
|
if (_class == CLASS_ACK) {
|
|
|
|
Debug("ACK %u", (unsigned)_msg_id);
|
2015-10-28 21:32:57 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
if(_msg_id == MSG_ACK_ACK) {
|
|
|
|
switch(_buffer.ack.clsID) {
|
|
|
|
case CLASS_CFG:
|
|
|
|
switch(_buffer.ack.msgID) {
|
|
|
|
case MSG_CFG_CFG:
|
|
|
|
_cfg_saved = true;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = false;
|
2016-02-02 03:58:33 -04:00
|
|
|
break;
|
|
|
|
case MSG_CFG_GNSS:
|
|
|
|
_unconfigured_messages &= ~CONFIG_GNSS;
|
|
|
|
break;
|
|
|
|
case MSG_CFG_MSG:
|
|
|
|
// There is no way to know what MSG config was ack'ed, assume it was the last
|
|
|
|
// one requested. To verify it rerequest the last config we sent. If we miss
|
|
|
|
// the actual ack we will catch it next time through the poll loop, but that
|
|
|
|
// will be a good chunk of time later.
|
|
|
|
break;
|
|
|
|
case MSG_CFG_NAV_SETTINGS:
|
|
|
|
_unconfigured_messages &= ~CONFIG_NAV_SETTINGS;
|
|
|
|
break;
|
|
|
|
case MSG_CFG_RATE:
|
2016-10-01 04:42:47 -03:00
|
|
|
// The GPS will ACK a update rate that is invalid. in order to detect this
|
|
|
|
// only accept the rate as configured by reading the settings back and
|
2019-01-04 00:40:41 -04:00
|
|
|
// validating that they all match the target values
|
2016-02-02 03:58:33 -04:00
|
|
|
break;
|
|
|
|
case MSG_CFG_SBAS:
|
|
|
|
_unconfigured_messages &= ~CONFIG_SBAS;
|
|
|
|
break;
|
2018-06-22 02:25:27 -03:00
|
|
|
case MSG_CFG_TP5:
|
|
|
|
_unconfigured_messages &= ~CONFIG_TP5;
|
|
|
|
break;
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case CLASS_MON:
|
|
|
|
switch(_buffer.ack.msgID) {
|
|
|
|
case MSG_MON_HW:
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_MON_HW;
|
|
|
|
break;
|
|
|
|
case MSG_MON_HW2:
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_MON_HW2;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2015-10-28 21:32:57 -03:00
|
|
|
}
|
2012-08-21 23:19:52 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
if (_class == CLASS_CFG) {
|
|
|
|
switch(_msg_id) {
|
|
|
|
case MSG_CFG_NAV_SETTINGS:
|
|
|
|
Debug("Got settings %u min_elev %d drLimit %u\n",
|
|
|
|
(unsigned)_buffer.nav_settings.dynModel,
|
|
|
|
(int)_buffer.nav_settings.minElev,
|
|
|
|
(unsigned)_buffer.nav_settings.drLimit);
|
|
|
|
_buffer.nav_settings.mask = 0;
|
|
|
|
if (gps._navfilter != AP_GPS::GPS_ENGINE_NONE &&
|
|
|
|
_buffer.nav_settings.dynModel != gps._navfilter) {
|
|
|
|
// we've received the current nav settings, change the engine
|
|
|
|
// settings and send them back
|
|
|
|
Debug("Changing engine setting from %u to %u\n",
|
|
|
|
(unsigned)_buffer.nav_settings.dynModel, (unsigned)gps._navfilter);
|
|
|
|
_buffer.nav_settings.dynModel = gps._navfilter;
|
|
|
|
_buffer.nav_settings.mask |= 1;
|
|
|
|
}
|
|
|
|
if (gps._min_elevation != -100 &&
|
|
|
|
_buffer.nav_settings.minElev != gps._min_elevation) {
|
|
|
|
Debug("Changing min elevation to %d\n", (int)gps._min_elevation);
|
|
|
|
_buffer.nav_settings.minElev = gps._min_elevation;
|
|
|
|
_buffer.nav_settings.mask |= 2;
|
|
|
|
}
|
|
|
|
if (_buffer.nav_settings.mask != 0) {
|
|
|
|
_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS,
|
|
|
|
&_buffer.nav_settings,
|
|
|
|
sizeof(_buffer.nav_settings));
|
|
|
|
_unconfigured_messages |= CONFIG_NAV_SETTINGS;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_NAV_SETTINGS;
|
|
|
|
}
|
|
|
|
return false;
|
2012-08-21 23:19:52 -03:00
|
|
|
|
2015-07-29 19:39:11 -03:00
|
|
|
#if UBLOX_GNSS_SETTINGS
|
2016-02-02 03:58:33 -04:00
|
|
|
case MSG_CFG_GNSS:
|
|
|
|
if (gps._gnss_mode[state.instance] != 0) {
|
|
|
|
struct ubx_cfg_gnss start_gnss = _buffer.gnss;
|
|
|
|
uint8_t gnssCount = 0;
|
|
|
|
Debug("Got GNSS Settings %u %u %u %u:\n",
|
|
|
|
(unsigned)_buffer.gnss.msgVer,
|
|
|
|
(unsigned)_buffer.gnss.numTrkChHw,
|
|
|
|
(unsigned)_buffer.gnss.numTrkChUse,
|
|
|
|
(unsigned)_buffer.gnss.numConfigBlocks);
|
2016-01-20 20:44:15 -04:00
|
|
|
#if UBLOX_DEBUGGING
|
2016-02-02 03:58:33 -04:00
|
|
|
for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
|
|
|
|
Debug(" %u %u %u 0x%08x\n",
|
|
|
|
(unsigned)_buffer.gnss.configBlock[i].gnssId,
|
|
|
|
(unsigned)_buffer.gnss.configBlock[i].resTrkCh,
|
|
|
|
(unsigned)_buffer.gnss.configBlock[i].maxTrkCh,
|
|
|
|
(unsigned)_buffer.gnss.configBlock[i].flags);
|
|
|
|
}
|
2015-07-14 18:12:47 -03:00
|
|
|
#endif
|
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
for(int i = 0; i < UBLOX_MAX_GNSS_CONFIG_BLOCKS; i++) {
|
|
|
|
if((gps._gnss_mode[state.instance] & (1 << i)) && i != GNSS_SBAS) {
|
|
|
|
gnssCount++;
|
|
|
|
}
|
|
|
|
}
|
2015-07-14 18:12:47 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
|
|
|
|
// Reserve an equal portion of channels for all enabled systems
|
|
|
|
if(gps._gnss_mode[state.instance] & (1 << _buffer.gnss.configBlock[i].gnssId)) {
|
|
|
|
if(GNSS_SBAS !=_buffer.gnss.configBlock[i].gnssId) {
|
|
|
|
_buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2);
|
|
|
|
_buffer.gnss.configBlock[i].maxTrkCh = _buffer.gnss.numTrkChHw;
|
|
|
|
} else {
|
|
|
|
_buffer.gnss.configBlock[i].resTrkCh = 1;
|
|
|
|
_buffer.gnss.configBlock[i].maxTrkCh = 3;
|
|
|
|
}
|
|
|
|
_buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags | 0x00000001;
|
|
|
|
} else {
|
|
|
|
_buffer.gnss.configBlock[i].resTrkCh = 0;
|
|
|
|
_buffer.gnss.configBlock[i].maxTrkCh = 0;
|
|
|
|
_buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags & 0xFFFFFFFE;
|
|
|
|
}
|
|
|
|
}
|
2018-03-28 11:48:44 -03:00
|
|
|
if (memcmp(&start_gnss, &_buffer.gnss, sizeof(start_gnss))) {
|
2016-02-02 03:58:33 -04:00
|
|
|
_send_message(CLASS_CFG, MSG_CFG_GNSS, &_buffer.gnss, 4 + (8 * _buffer.gnss.numConfigBlocks));
|
|
|
|
_unconfigured_messages |= CONFIG_GNSS;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2015-07-14 18:12:47 -03:00
|
|
|
} else {
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages &= ~CONFIG_GNSS;
|
2015-07-14 18:12:47 -03:00
|
|
|
}
|
|
|
|
} else {
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages &= ~CONFIG_GNSS;
|
2015-07-14 18:12:47 -03:00
|
|
|
}
|
2016-02-02 03:58:33 -04:00
|
|
|
return false;
|
2015-07-29 21:21:42 -03:00
|
|
|
#endif
|
2015-07-14 18:12:47 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
case MSG_CFG_SBAS:
|
|
|
|
if (gps._sbas_mode != 2) {
|
|
|
|
Debug("Got SBAS settings %u %u %u 0x%x 0x%x\n",
|
|
|
|
(unsigned)_buffer.sbas.mode,
|
|
|
|
(unsigned)_buffer.sbas.usage,
|
|
|
|
(unsigned)_buffer.sbas.maxSBAS,
|
|
|
|
(unsigned)_buffer.sbas.scanmode2,
|
|
|
|
(unsigned)_buffer.sbas.scanmode1);
|
|
|
|
if (_buffer.sbas.mode != gps._sbas_mode) {
|
|
|
|
_buffer.sbas.mode = gps._sbas_mode;
|
|
|
|
_send_message(CLASS_CFG, MSG_CFG_SBAS,
|
|
|
|
&_buffer.sbas,
|
|
|
|
sizeof(_buffer.sbas));
|
|
|
|
_unconfigured_messages |= CONFIG_SBAS;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_SBAS;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_SBAS;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
case MSG_CFG_MSG:
|
|
|
|
if(_payload_length == sizeof(ubx_cfg_msg_rate_6)) {
|
|
|
|
// can't verify the setting without knowing the port
|
|
|
|
// request the port again
|
|
|
|
if(_ublox_port >= UBLOX_MAX_PORTS) {
|
|
|
|
_request_port();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
_verify_rate(_buffer.msg_rate_6.msg_class, _buffer.msg_rate_6.msg_id,
|
|
|
|
_buffer.msg_rate_6.rates[_ublox_port]);
|
|
|
|
} else {
|
|
|
|
_verify_rate(_buffer.msg_rate.msg_class, _buffer.msg_rate.msg_id,
|
|
|
|
_buffer.msg_rate.rate);
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
case MSG_CFG_PRT:
|
|
|
|
_ublox_port = _buffer.prt.portID;
|
|
|
|
return false;
|
|
|
|
case MSG_CFG_RATE:
|
2016-10-01 04:42:47 -03:00
|
|
|
if(_buffer.nav_rate.measure_rate_ms != gps._rate_ms[state.instance] ||
|
2016-02-02 03:58:33 -04:00
|
|
|
_buffer.nav_rate.nav_rate != 1 ||
|
|
|
|
_buffer.nav_rate.timeref != 0) {
|
|
|
|
_configure_rate();
|
|
|
|
_unconfigured_messages |= CONFIG_RATE_NAV;
|
2016-02-12 16:32:08 -04:00
|
|
|
_cfg_needs_save = true;
|
2016-02-02 03:58:33 -04:00
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_RATE_NAV;
|
|
|
|
}
|
|
|
|
return false;
|
2018-06-22 02:25:27 -03:00
|
|
|
|
|
|
|
#if CONFIGURE_PPS_PIN
|
|
|
|
case MSG_CFG_TP5: {
|
|
|
|
// configure the PPS pin for 1Hz, zero delay
|
|
|
|
Debug("Got TP5 ver=%u 0x%04x %u\n",
|
|
|
|
(unsigned)_buffer.nav_tp5.version,
|
|
|
|
(unsigned)_buffer.nav_tp5.flags,
|
|
|
|
(unsigned)_buffer.nav_tp5.freqPeriod);
|
|
|
|
const uint16_t desired_flags = 0x003f;
|
|
|
|
const uint16_t desired_period_hz = 1;
|
|
|
|
if (_buffer.nav_tp5.flags != desired_flags ||
|
|
|
|
_buffer.nav_tp5.freqPeriod != desired_period_hz) {
|
|
|
|
_buffer.nav_tp5.tpIdx = 0;
|
|
|
|
_buffer.nav_tp5.reserved1[0] = 0;
|
|
|
|
_buffer.nav_tp5.reserved1[1] = 0;
|
|
|
|
_buffer.nav_tp5.antCableDelay = 0;
|
|
|
|
_buffer.nav_tp5.rfGroupDelay = 0;
|
|
|
|
_buffer.nav_tp5.freqPeriod = desired_period_hz;
|
|
|
|
_buffer.nav_tp5.freqPeriodLock = desired_period_hz;
|
|
|
|
_buffer.nav_tp5.pulseLenRatio = 1;
|
|
|
|
_buffer.nav_tp5.pulseLenRatioLock = 2;
|
|
|
|
_buffer.nav_tp5.userConfigDelay = 0;
|
|
|
|
_buffer.nav_tp5.flags = desired_flags;
|
|
|
|
_send_message(CLASS_CFG, MSG_CFG_TP5,
|
|
|
|
&_buffer.nav_tp5,
|
|
|
|
sizeof(_buffer.nav_tp5));
|
|
|
|
_unconfigured_messages |= CONFIG_TP5;
|
|
|
|
_cfg_needs_save = true;
|
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_TP5;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif // CONFIGURE_PPS_PIN
|
2019-11-05 23:43:41 -04:00
|
|
|
case MSG_CFG_VALGET: {
|
|
|
|
uint8_t cfg_len = _payload_length - sizeof(ubx_cfg_valget);
|
|
|
|
const uint8_t *cfg_data = (const uint8_t *)(&_buffer) + sizeof(ubx_cfg_valget);
|
|
|
|
while (cfg_len >= 5) {
|
|
|
|
ConfigKey id;
|
|
|
|
memcpy(&id, cfg_data, sizeof(uint32_t));
|
|
|
|
cfg_len -= 4;
|
|
|
|
cfg_data += 4;
|
|
|
|
switch (id) {
|
|
|
|
case ConfigKey::TMODE_MODE: {
|
|
|
|
uint8_t mode = cfg_data[0];
|
|
|
|
cfg_len -= 1;
|
|
|
|
cfg_data += 1;
|
|
|
|
if (mode != 0) {
|
|
|
|
// ask for mode 0, to disable TIME mode
|
|
|
|
mode = 0;
|
|
|
|
_configure_valset(ConfigKey::TMODE_MODE, 1, &mode);
|
|
|
|
_unconfigured_messages |= CONFIG_TMODE_MODE;
|
|
|
|
} else {
|
|
|
|
_unconfigured_messages &= ~CONFIG_TMODE_MODE;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
default:
|
|
|
|
// we don't know the length so we stop parsing
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2014-09-04 01:27:05 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-03-23 22:02:37 -03:00
|
|
|
if (_class == CLASS_MON) {
|
2016-02-02 03:58:33 -04:00
|
|
|
switch(_msg_id) {
|
|
|
|
case MSG_MON_HW:
|
2014-04-02 20:55:05 -03:00
|
|
|
if (_payload_length == 60 || _payload_length == 68) {
|
|
|
|
log_mon_hw();
|
|
|
|
}
|
2016-02-02 03:58:33 -04:00
|
|
|
break;
|
|
|
|
case MSG_MON_HW2:
|
2014-04-02 20:55:05 -03:00
|
|
|
if (_payload_length == 28) {
|
|
|
|
log_mon_hw2();
|
|
|
|
}
|
2016-02-02 03:58:33 -04:00
|
|
|
break;
|
|
|
|
case MSG_MON_VER:
|
|
|
|
_have_version = true;
|
2016-08-02 02:48:16 -03:00
|
|
|
strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion));
|
|
|
|
strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion));
|
2019-05-26 22:34:13 -03:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
|
2016-02-23 23:26:57 -04:00
|
|
|
"u-blox %d HW: %s SW: %s",
|
2016-08-02 04:31:11 -03:00
|
|
|
state.instance + 1,
|
2016-08-02 02:48:16 -03:00
|
|
|
_version.hwVersion,
|
|
|
|
_version.swVersion);
|
2019-07-01 01:51:56 -03:00
|
|
|
// check for F9. The F9 does not respond to SVINFO, so we need to use MON_VER
|
|
|
|
// for hardware generation
|
|
|
|
if (strncmp(_version.hwVersion, "00190000", 8) == 0) {
|
2019-11-12 07:03:37 -04:00
|
|
|
if (_hardware_generation != UBLOX_F9) {
|
|
|
|
// need to ensure time mode is correctly setup on F9
|
|
|
|
_unconfigured_messages |= CONFIG_TMODE_MODE;
|
|
|
|
}
|
2019-07-01 01:51:56 -03:00
|
|
|
_hardware_generation = UBLOX_F9;
|
|
|
|
}
|
2016-02-02 03:58:33 -04:00
|
|
|
break;
|
|
|
|
default:
|
2014-03-23 22:02:37 -03:00
|
|
|
unexpected_message();
|
2012-08-21 23:19:52 -03:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2014-03-23 22:02:37 -03:00
|
|
|
|
2015-05-04 05:18:34 -03:00
|
|
|
#if UBLOX_RXM_RAW_LOGGING
|
|
|
|
if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAW && gps._raw_data != 0) {
|
|
|
|
log_rxm_raw(_buffer.rxm_raw);
|
|
|
|
return false;
|
2015-06-29 19:04:35 -03:00
|
|
|
} else if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAWX && gps._raw_data != 0) {
|
|
|
|
log_rxm_rawx(_buffer.rxm_rawx);
|
|
|
|
return false;
|
2015-05-04 05:18:34 -03:00
|
|
|
}
|
|
|
|
#endif // UBLOX_RXM_RAW_LOGGING
|
|
|
|
|
2014-03-23 22:02:37 -03:00
|
|
|
if (_class != CLASS_NAV) {
|
|
|
|
unexpected_message();
|
|
|
|
return false;
|
|
|
|
}
|
2012-06-10 03:34:13 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
switch (_msg_id) {
|
|
|
|
case MSG_POSLLH:
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("MSG_POSLLH next_fix=%u", next_fix);
|
2016-07-30 20:38:43 -03:00
|
|
|
if (havePvtMsg) {
|
2017-01-12 02:19:35 -04:00
|
|
|
_unconfigured_messages |= CONFIG_RATE_POSLLH;
|
2016-07-30 20:38:43 -03:00
|
|
|
break;
|
|
|
|
}
|
2018-05-15 22:16:01 -03:00
|
|
|
_check_new_itow(_buffer.posllh.itow);
|
|
|
|
_last_pos_time = _buffer.posllh.itow;
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.lng = _buffer.posllh.longitude;
|
|
|
|
state.location.lat = _buffer.posllh.latitude;
|
|
|
|
state.location.alt = _buffer.posllh.altitude_msl / 10;
|
|
|
|
state.status = next_fix;
|
2012-08-21 23:19:52 -03:00
|
|
|
_new_position = true;
|
2015-09-03 22:49:23 -03:00
|
|
|
state.horizontal_accuracy = _buffer.posllh.horizontal_accuracy*1.0e-3f;
|
|
|
|
state.vertical_accuracy = _buffer.posllh.vertical_accuracy*1.0e-3f;
|
|
|
|
state.have_horizontal_accuracy = true;
|
|
|
|
state.have_vertical_accuracy = true;
|
2013-10-10 05:15:07 -03:00
|
|
|
#if UBLOX_FAKE_3DLOCK
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.lng = 1491652300L;
|
|
|
|
state.location.lat = -353632610L;
|
|
|
|
state.location.alt = 58400;
|
2015-09-03 22:49:23 -03:00
|
|
|
state.vertical_accuracy = 0;
|
|
|
|
state.horizontal_accuracy = 0;
|
2013-10-10 05:15:07 -03:00
|
|
|
#endif
|
2012-08-21 23:19:52 -03:00
|
|
|
break;
|
2011-10-28 15:52:50 -03:00
|
|
|
case MSG_STATUS:
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("MSG_STATUS fix_status=%u fix_type=%u",
|
|
|
|
_buffer.status.fix_status,
|
|
|
|
_buffer.status.fix_type);
|
2018-06-22 02:26:09 -03:00
|
|
|
_check_new_itow(_buffer.status.itow);
|
2016-07-30 20:38:43 -03:00
|
|
|
if (havePvtMsg) {
|
2017-01-12 02:19:35 -04:00
|
|
|
_unconfigured_messages |= CONFIG_RATE_STATUS;
|
2016-07-30 20:38:43 -03:00
|
|
|
break;
|
|
|
|
}
|
2013-03-25 07:08:47 -03:00
|
|
|
if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) {
|
2015-06-18 11:53:28 -03:00
|
|
|
if( (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) &&
|
|
|
|
(_buffer.status.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) {
|
|
|
|
next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS;
|
|
|
|
}else if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) {
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::GPS_OK_FIX_3D;
|
2013-03-25 07:08:47 -03:00
|
|
|
}else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) {
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::GPS_OK_FIX_2D;
|
2013-03-25 07:08:47 -03:00
|
|
|
}else{
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::NO_FIX;
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
2013-03-25 07:08:47 -03:00
|
|
|
}
|
2013-03-25 04:24:14 -03:00
|
|
|
}else{
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::NO_FIX;
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
2012-08-21 23:19:52 -03:00
|
|
|
}
|
2013-10-02 03:10:22 -03:00
|
|
|
#if UBLOX_FAKE_3DLOCK
|
2014-03-28 16:52:27 -03:00
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
|
|
|
next_fix = state.status;
|
2015-07-14 02:09:43 -03:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
case MSG_DOP:
|
|
|
|
Debug("MSG_DOP");
|
2015-08-07 09:49:36 -03:00
|
|
|
noReceivedHdop = false;
|
2018-05-15 22:16:01 -03:00
|
|
|
_check_new_itow(_buffer.dop.itow);
|
2015-07-14 02:09:43 -03:00
|
|
|
state.hdop = _buffer.dop.hDOP;
|
2015-09-07 19:22:12 -03:00
|
|
|
state.vdop = _buffer.dop.vDOP;
|
2015-07-14 02:09:43 -03:00
|
|
|
#if UBLOX_FAKE_3DLOCK
|
2015-07-14 02:14:25 -03:00
|
|
|
state.hdop = 130;
|
2015-09-07 19:22:12 -03:00
|
|
|
state.hdop = 170;
|
2013-10-02 03:10:22 -03:00
|
|
|
#endif
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
case MSG_SOL:
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("MSG_SOL fix_status=%u fix_type=%u",
|
|
|
|
_buffer.solution.fix_status,
|
|
|
|
_buffer.solution.fix_type);
|
2018-05-15 22:16:01 -03:00
|
|
|
_check_new_itow(_buffer.solution.itow);
|
2016-07-30 20:38:43 -03:00
|
|
|
if (havePvtMsg) {
|
|
|
|
state.time_week = _buffer.solution.week;
|
|
|
|
break;
|
|
|
|
}
|
2013-03-25 21:21:47 -03:00
|
|
|
if (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) {
|
2015-06-18 11:53:28 -03:00
|
|
|
if( (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) &&
|
|
|
|
(_buffer.solution.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) {
|
|
|
|
next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS;
|
|
|
|
}else if( _buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) {
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::GPS_OK_FIX_3D;
|
2013-03-25 21:21:47 -03:00
|
|
|
}else if (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_2D) {
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::GPS_OK_FIX_2D;
|
2013-03-25 07:08:47 -03:00
|
|
|
}else{
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::NO_FIX;
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
2013-03-25 07:08:47 -03:00
|
|
|
}
|
2013-03-25 04:24:14 -03:00
|
|
|
}else{
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = AP_GPS::NO_FIX;
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
2012-08-21 23:19:52 -03:00
|
|
|
}
|
2015-08-07 09:49:36 -03:00
|
|
|
if(noReceivedHdop) {
|
2015-08-07 07:20:55 -03:00
|
|
|
state.hdop = _buffer.solution.position_DOP;
|
|
|
|
}
|
2014-03-28 16:52:27 -03:00
|
|
|
state.num_sats = _buffer.solution.satellites;
|
|
|
|
if (next_fix >= AP_GPS::GPS_OK_FIX_2D) {
|
2015-11-19 23:10:22 -04:00
|
|
|
state.last_gps_time_ms = AP_HAL::millis();
|
2018-05-15 22:16:01 -03:00
|
|
|
state.time_week_ms = _buffer.solution.itow;
|
2014-03-28 16:52:27 -03:00
|
|
|
state.time_week = _buffer.solution.week;
|
2013-10-23 08:13:48 -03:00
|
|
|
}
|
2013-10-02 03:10:22 -03:00
|
|
|
#if UBLOX_FAKE_3DLOCK
|
2014-03-28 16:52:27 -03:00
|
|
|
next_fix = state.status;
|
|
|
|
state.num_sats = 10;
|
|
|
|
state.time_week = 1721;
|
2015-11-19 23:10:22 -04:00
|
|
|
state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
|
|
|
|
state.last_gps_time_ms = AP_HAL::millis();
|
2015-09-03 22:49:23 -03:00
|
|
|
state.hdop = 130;
|
2013-10-02 03:10:22 -03:00
|
|
|
#endif
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
2016-07-30 20:38:43 -03:00
|
|
|
case MSG_PVT:
|
|
|
|
Debug("MSG_PVT");
|
|
|
|
havePvtMsg = true;
|
|
|
|
// position
|
2018-05-15 22:16:01 -03:00
|
|
|
_check_new_itow(_buffer.pvt.itow);
|
2016-07-30 20:38:43 -03:00
|
|
|
_last_pos_time = _buffer.pvt.itow;
|
|
|
|
state.location.lng = _buffer.pvt.lon;
|
|
|
|
state.location.lat = _buffer.pvt.lat;
|
|
|
|
state.location.alt = _buffer.pvt.h_msl / 10;
|
|
|
|
switch (_buffer.pvt.fix_type)
|
|
|
|
{
|
|
|
|
case 0:
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
|
|
|
break;
|
|
|
|
case 1:
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
|
|
|
break;
|
|
|
|
case 2:
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_2D;
|
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
|
|
|
if (_buffer.pvt.flags & 0b00000010) // diffsoln
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
|
|
|
|
if (_buffer.pvt.flags & 0b01000000) // carrsoln - float
|
2016-10-16 21:56:34 -03:00
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
|
2016-07-30 20:38:43 -03:00
|
|
|
if (_buffer.pvt.flags & 0b10000000) // carrsoln - fixed
|
2016-10-16 21:56:34 -03:00
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
|
2016-07-30 20:38:43 -03:00
|
|
|
break;
|
|
|
|
case 4:
|
2019-05-26 22:34:13 -03:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
|
2016-10-16 21:56:34 -03:00
|
|
|
"Unexpected state %d", _buffer.pvt.flags);
|
2016-07-30 20:38:43 -03:00
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
|
|
|
break;
|
|
|
|
case 5:
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
next_fix = state.status;
|
|
|
|
_new_position = true;
|
|
|
|
state.horizontal_accuracy = _buffer.pvt.h_acc*1.0e-3f;
|
|
|
|
state.vertical_accuracy = _buffer.pvt.v_acc*1.0e-3f;
|
|
|
|
state.have_horizontal_accuracy = true;
|
|
|
|
state.have_vertical_accuracy = true;
|
|
|
|
// SVs
|
|
|
|
state.num_sats = _buffer.pvt.num_sv;
|
|
|
|
// velocity
|
|
|
|
_last_vel_time = _buffer.pvt.itow;
|
|
|
|
state.ground_speed = _buffer.pvt.gspeed*0.001f; // m/s
|
|
|
|
state.ground_course = wrap_360(_buffer.pvt.head_mot * 1.0e-5f); // Heading 2D deg * 100000
|
|
|
|
state.have_vertical_velocity = true;
|
|
|
|
state.velocity.x = _buffer.pvt.velN * 0.001f;
|
|
|
|
state.velocity.y = _buffer.pvt.velE * 0.001f;
|
|
|
|
state.velocity.z = _buffer.pvt.velD * 0.001f;
|
|
|
|
state.have_speed_accuracy = true;
|
|
|
|
state.speed_accuracy = _buffer.pvt.s_acc*0.001f;
|
|
|
|
_new_speed = true;
|
|
|
|
// dop
|
|
|
|
if(noReceivedHdop) {
|
|
|
|
state.hdop = _buffer.pvt.p_dop;
|
|
|
|
state.vdop = _buffer.pvt.p_dop;
|
|
|
|
}
|
|
|
|
|
|
|
|
state.last_gps_time_ms = AP_HAL::millis();
|
|
|
|
|
|
|
|
// time
|
|
|
|
state.time_week_ms = _buffer.pvt.itow;
|
2017-02-20 04:43:31 -04:00
|
|
|
#if UBLOX_FAKE_3DLOCK
|
|
|
|
state.location.lng = 1491652300L;
|
|
|
|
state.location.lat = -353632610L;
|
|
|
|
state.location.alt = 58400;
|
|
|
|
state.vertical_accuracy = 0;
|
|
|
|
state.horizontal_accuracy = 0;
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
|
|
|
state.num_sats = 10;
|
|
|
|
state.time_week = 1721;
|
|
|
|
state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
|
|
|
|
state.last_gps_time_ms = AP_HAL::millis();
|
|
|
|
state.hdop = 130;
|
2018-06-03 06:21:49 -03:00
|
|
|
state.speed_accuracy = 0;
|
2017-02-20 04:43:31 -04:00
|
|
|
next_fix = state.status;
|
|
|
|
#endif
|
2016-07-30 20:38:43 -03:00
|
|
|
break;
|
2019-03-30 01:21:11 -03:00
|
|
|
case MSG_TIMEGPS:
|
|
|
|
Debug("MSG_TIMEGPS");
|
|
|
|
_check_new_itow(_buffer.timegps.itow);
|
2019-07-01 01:51:56 -03:00
|
|
|
if (_buffer.timegps.valid & UBX_TIMEGPS_VALID_WEEK_MASK) {
|
2019-03-30 01:21:11 -03:00
|
|
|
state.time_week = _buffer.timegps.week;
|
2019-07-01 01:51:56 -03:00
|
|
|
}
|
2019-03-30 01:21:11 -03:00
|
|
|
break;
|
2011-10-28 15:52:50 -03:00
|
|
|
case MSG_VELNED:
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("MSG_VELNED");
|
2016-07-30 20:38:43 -03:00
|
|
|
if (havePvtMsg) {
|
2017-01-12 02:19:35 -04:00
|
|
|
_unconfigured_messages |= CONFIG_RATE_VELNED;
|
2016-07-30 20:38:43 -03:00
|
|
|
break;
|
|
|
|
}
|
2018-05-15 22:16:01 -03:00
|
|
|
_check_new_itow(_buffer.velned.itow);
|
|
|
|
_last_vel_time = _buffer.velned.itow;
|
2014-03-28 16:52:27 -03:00
|
|
|
state.ground_speed = _buffer.velned.speed_2d*0.01f; // m/s
|
2016-05-04 22:28:35 -03:00
|
|
|
state.ground_course = wrap_360(_buffer.velned.heading_2d * 1.0e-5f); // Heading 2D deg * 100000
|
2014-03-28 16:52:27 -03:00
|
|
|
state.have_vertical_velocity = true;
|
|
|
|
state.velocity.x = _buffer.velned.ned_north * 0.01f;
|
|
|
|
state.velocity.y = _buffer.velned.ned_east * 0.01f;
|
|
|
|
state.velocity.z = _buffer.velned.ned_down * 0.01f;
|
2016-05-05 02:28:15 -03:00
|
|
|
state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x)));
|
2016-04-16 06:58:46 -03:00
|
|
|
state.ground_speed = norm(state.velocity.y, state.velocity.x);
|
2014-10-28 16:44:07 -03:00
|
|
|
state.have_speed_accuracy = true;
|
|
|
|
state.speed_accuracy = _buffer.velned.speed_accuracy*0.01f;
|
2015-09-03 22:49:23 -03:00
|
|
|
#if UBLOX_FAKE_3DLOCK
|
|
|
|
state.speed_accuracy = 0;
|
|
|
|
#endif
|
2012-08-21 23:19:52 -03:00
|
|
|
_new_speed = true;
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
2015-04-01 08:49:34 -03:00
|
|
|
case MSG_NAV_SVINFO:
|
|
|
|
{
|
|
|
|
Debug("MSG_NAV_SVINFO\n");
|
|
|
|
static const uint8_t HardwareGenerationMask = 0x07;
|
2018-05-15 22:16:01 -03:00
|
|
|
_check_new_itow(_buffer.svinfo_header.itow);
|
2016-02-02 03:58:33 -04:00
|
|
|
_hardware_generation = _buffer.svinfo_header.globalFlags & HardwareGenerationMask;
|
|
|
|
switch (_hardware_generation) {
|
2015-04-01 08:49:34 -03:00
|
|
|
case UBLOX_5:
|
|
|
|
case UBLOX_6:
|
2016-02-02 03:58:33 -04:00
|
|
|
// only 7 and newer support CONFIG_GNSS
|
|
|
|
_unconfigured_messages &= ~CONFIG_GNSS;
|
2015-04-01 08:49:34 -03:00
|
|
|
break;
|
|
|
|
case UBLOX_7:
|
|
|
|
case UBLOX_M8:
|
2016-02-02 03:58:33 -04:00
|
|
|
#if UBLOX_SPEED_CHANGE
|
2015-04-01 08:49:34 -03:00
|
|
|
port->begin(4000000U);
|
2016-02-02 03:58:33 -04:00
|
|
|
Debug("Changed speed to 4Mhz for SPI-driven UBlox\n");
|
|
|
|
#endif
|
2015-04-01 08:49:34 -03:00
|
|
|
break;
|
|
|
|
default:
|
2016-02-02 03:58:33 -04:00
|
|
|
hal.console->printf("Wrong Ublox Hardware Version%u\n", _hardware_generation);
|
2015-04-01 08:49:34 -03:00
|
|
|
break;
|
|
|
|
};
|
2016-02-02 03:58:33 -04:00
|
|
|
_unconfigured_messages &= ~CONFIG_VERSION;
|
2015-04-01 08:49:34 -03:00
|
|
|
/* We don't need that anymore */
|
|
|
|
_configure_message_rate(CLASS_NAV, MSG_NAV_SVINFO, 0);
|
|
|
|
break;
|
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
default:
|
2012-08-21 23:19:52 -03:00
|
|
|
Debug("Unexpected NAV message 0x%02x", (unsigned)_msg_id);
|
|
|
|
if (++_disable_counter == 0) {
|
|
|
|
Debug("Disabling NAV message 0x%02x", (unsigned)_msg_id);
|
|
|
|
_configure_message_rate(CLASS_NAV, _msg_id, 0);
|
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
return false;
|
|
|
|
}
|
2012-06-08 03:39:12 -03:00
|
|
|
|
2012-08-21 23:19:52 -03:00
|
|
|
// we only return true when we get new position and speed data
|
|
|
|
// this ensures we don't use stale data
|
2014-04-14 19:23:12 -03:00
|
|
|
if (_new_position && _new_speed && _last_vel_time == _last_pos_time) {
|
2012-08-21 23:19:52 -03:00
|
|
|
_new_speed = _new_position = false;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
2012-06-10 03:34:13 -03:00
|
|
|
|
|
|
|
|
|
|
|
// UBlox auto configuration
|
|
|
|
|
|
|
|
/*
|
2012-08-21 23:19:52 -03:00
|
|
|
* update checksum for a set of bytes
|
2012-06-10 03:34:13 -03:00
|
|
|
*/
|
|
|
|
void
|
2015-05-04 05:18:34 -03:00
|
|
|
AP_GPS_UBLOX::_update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b)
|
2012-06-10 03:34:13 -03:00
|
|
|
{
|
2012-08-21 23:19:52 -03:00
|
|
|
while (len--) {
|
|
|
|
ck_a += *data;
|
|
|
|
ck_b += ck_a;
|
|
|
|
data++;
|
|
|
|
}
|
2012-06-10 03:34:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
2012-08-21 23:19:52 -03:00
|
|
|
* send a ublox message
|
2012-06-10 03:34:13 -03:00
|
|
|
*/
|
2017-02-15 19:20:21 -04:00
|
|
|
bool
|
2015-05-04 05:18:34 -03:00
|
|
|
AP_GPS_UBLOX::_send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size)
|
2012-06-10 03:34:13 -03:00
|
|
|
{
|
2017-02-15 19:20:21 -04:00
|
|
|
if (port->txspace() < (sizeof(struct ubx_header) + 2 + size)) {
|
|
|
|
return false;
|
|
|
|
}
|
2012-08-21 23:19:52 -03:00
|
|
|
struct ubx_header header;
|
|
|
|
uint8_t ck_a=0, ck_b=0;
|
|
|
|
header.preamble1 = PREAMBLE1;
|
|
|
|
header.preamble2 = PREAMBLE2;
|
|
|
|
header.msg_class = msg_class;
|
|
|
|
header.msg_id = msg_id;
|
|
|
|
header.length = size;
|
|
|
|
|
|
|
|
_update_checksum((uint8_t *)&header.msg_class, sizeof(header)-2, ck_a, ck_b);
|
|
|
|
_update_checksum((uint8_t *)msg, size, ck_a, ck_b);
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
port->write((const uint8_t *)&header, sizeof(header));
|
|
|
|
port->write((const uint8_t *)msg, size);
|
|
|
|
port->write((const uint8_t *)&ck_a, 1);
|
|
|
|
port->write((const uint8_t *)&ck_b, 1);
|
2017-02-15 19:20:21 -04:00
|
|
|
return true;
|
2012-06-10 03:34:13 -03:00
|
|
|
}
|
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
/*
|
|
|
|
* requests the given message rate for a specific message class
|
|
|
|
* and msg_id
|
|
|
|
* returns true if it sent the request, false if waiting on knowing the port
|
|
|
|
*/
|
|
|
|
bool
|
|
|
|
AP_GPS_UBLOX::_request_message_rate(uint8_t msg_class, uint8_t msg_id)
|
|
|
|
{
|
|
|
|
// Without knowing what communication port is being used it isn't possible to verify
|
|
|
|
// always ensure we have a port before sending the request
|
|
|
|
if(_ublox_port >= UBLOX_MAX_PORTS) {
|
|
|
|
_request_port();
|
|
|
|
return false;
|
|
|
|
} else {
|
|
|
|
struct ubx_cfg_msg msg;
|
|
|
|
msg.msg_class = msg_class;
|
|
|
|
msg.msg_id = msg_id;
|
2017-02-15 19:20:21 -04:00
|
|
|
return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
}
|
2012-06-10 03:34:13 -03:00
|
|
|
|
|
|
|
/*
|
2012-08-21 23:19:52 -03:00
|
|
|
* configure a UBlox GPS for the given message rate for a specific
|
|
|
|
* message class and msg_id
|
2012-06-10 03:34:13 -03:00
|
|
|
*/
|
2016-02-02 03:58:33 -04:00
|
|
|
bool
|
2012-06-10 03:34:13 -03:00
|
|
|
AP_GPS_UBLOX::_configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
|
|
|
|
{
|
2016-02-02 03:58:33 -04:00
|
|
|
if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_msg_rate)+2)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2012-08-21 23:19:52 -03:00
|
|
|
struct ubx_cfg_msg_rate msg;
|
|
|
|
msg.msg_class = msg_class;
|
|
|
|
msg.msg_id = msg_id;
|
2016-10-16 21:56:34 -03:00
|
|
|
msg.rate = rate;
|
2017-02-15 19:20:21 -04:00
|
|
|
return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
|
2013-10-01 23:32:32 -03:00
|
|
|
}
|
|
|
|
|
2019-11-05 23:43:41 -04:00
|
|
|
/*
|
|
|
|
* configure F9 based key/value pair - VALSET
|
|
|
|
*/
|
|
|
|
bool
|
|
|
|
AP_GPS_UBLOX::_configure_valset(ConfigKey key, const uint8_t len, const uint8_t *value)
|
|
|
|
{
|
|
|
|
if (_hardware_generation < UBLOX_F9) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
struct ubx_cfg_valset msg {};
|
|
|
|
uint8_t buf[sizeof(msg)+len];
|
|
|
|
if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(buf)+2)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
msg.version = 1;
|
|
|
|
msg.layers = 7; // all layers
|
|
|
|
msg.transaction = 0;
|
|
|
|
msg.key = uint32_t(key);
|
|
|
|
memcpy(buf, &msg, sizeof(msg));
|
|
|
|
memcpy(&buf[sizeof(msg)], value, len);
|
|
|
|
auto ret = _send_message(CLASS_CFG, MSG_CFG_VALSET, buf, sizeof(buf));
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* configure F9 based key/value pair - VALGET
|
|
|
|
*/
|
|
|
|
bool
|
|
|
|
AP_GPS_UBLOX::_configure_valget(ConfigKey key)
|
|
|
|
{
|
|
|
|
if (_hardware_generation < UBLOX_F9) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
struct {
|
|
|
|
struct ubx_cfg_valget msg;
|
|
|
|
ConfigKey key;
|
|
|
|
} msg {};
|
|
|
|
if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(msg)+2)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
msg.msg.version = 0;
|
|
|
|
msg.msg.layers = 0; // ram
|
|
|
|
msg.key = key;
|
|
|
|
return _send_message(CLASS_CFG, MSG_CFG_VALGET, &msg, sizeof(msg));
|
|
|
|
}
|
|
|
|
|
2015-10-28 21:32:57 -03:00
|
|
|
/*
|
2015-11-04 17:14:27 -04:00
|
|
|
* save gps configurations to non-volatile memory sent until the call of
|
|
|
|
* this message
|
2015-10-28 21:32:57 -03:00
|
|
|
*/
|
|
|
|
void
|
|
|
|
AP_GPS_UBLOX::_save_cfg()
|
|
|
|
{
|
|
|
|
ubx_cfg_cfg save_cfg;
|
|
|
|
save_cfg.clearMask = 0;
|
|
|
|
save_cfg.saveMask = SAVE_CFG_ALL;
|
|
|
|
save_cfg.loadMask = 0;
|
|
|
|
_send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg));
|
2016-02-02 03:58:33 -04:00
|
|
|
_last_cfg_sent_time = AP_HAL::millis();
|
|
|
|
_num_cfg_save_tries++;
|
2019-05-26 22:34:13 -03:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
|
2016-02-12 16:32:08 -04:00
|
|
|
"GPS: u-blox %d saving config",
|
2016-10-01 04:42:47 -03:00
|
|
|
state.instance + 1);
|
2015-10-28 21:32:57 -03:00
|
|
|
}
|
2012-09-17 01:43:07 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
detect a Ublox GPS. Adds one byte, and returns true if the stream
|
|
|
|
matches a UBlox
|
|
|
|
*/
|
|
|
|
bool
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_UBLOX::_detect(struct UBLOX_detect_state &state, uint8_t data)
|
2012-09-17 01:43:07 -03:00
|
|
|
{
|
2013-01-05 01:32:42 -04:00
|
|
|
reset:
|
2014-03-28 00:50:44 -03:00
|
|
|
switch (state.step) {
|
2012-09-17 01:43:07 -03:00
|
|
|
case 1:
|
|
|
|
if (PREAMBLE2 == data) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
}
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2017-08-22 14:28:10 -03:00
|
|
|
FALLTHROUGH;
|
2012-09-17 01:43:07 -03:00
|
|
|
case 0:
|
|
|
|
if (PREAMBLE1 == data)
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 2:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
state.ck_b = state.ck_a = data;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 3:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
state.ck_b += (state.ck_a += data);
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 4:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
state.ck_b += (state.ck_a += data);
|
|
|
|
state.payload_length = data;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 5:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
state.ck_b += (state.ck_a += data);
|
|
|
|
state.payload_counter = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 6:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.ck_b += (state.ck_a += data);
|
|
|
|
if (++state.payload_counter == state.payload_length)
|
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 7:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
if (state.ck_a != data) {
|
|
|
|
state.step = 0;
|
2013-01-05 01:32:42 -04:00
|
|
|
goto reset;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 8:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
|
|
|
if (state.ck_b == data) {
|
2012-09-17 01:43:07 -03:00
|
|
|
// a valid UBlox packet
|
|
|
|
return true;
|
2013-01-05 01:32:42 -04:00
|
|
|
} else {
|
|
|
|
goto reset;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2015-04-01 08:49:34 -03:00
|
|
|
|
|
|
|
void
|
|
|
|
AP_GPS_UBLOX::_request_version(void)
|
|
|
|
{
|
2016-10-30 02:24:21 -03:00
|
|
|
_send_message(CLASS_MON, MSG_MON_VER, nullptr, 0);
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void
|
|
|
|
AP_GPS_UBLOX::_configure_rate(void)
|
|
|
|
{
|
|
|
|
struct ubx_cfg_nav_rate msg;
|
2016-10-01 04:42:47 -03:00
|
|
|
// require a minimum measurement rate of 5Hz
|
2017-03-10 02:46:58 -04:00
|
|
|
msg.measure_rate_ms = gps.get_rate_ms(state.instance);
|
2016-02-02 03:58:33 -04:00
|
|
|
msg.nav_rate = 1;
|
|
|
|
msg.timeref = 0; // UTC time
|
|
|
|
_send_message(CLASS_CFG, MSG_CFG_RATE, &msg, sizeof(msg));
|
2015-04-01 08:49:34 -03:00
|
|
|
}
|
2016-03-16 20:43:21 -03:00
|
|
|
|
2016-04-12 00:16:20 -03:00
|
|
|
static const char *reasons[] = {"navigation rate",
|
|
|
|
"posllh rate",
|
|
|
|
"status rate",
|
|
|
|
"solution rate",
|
|
|
|
"velned rate",
|
|
|
|
"dop rate",
|
|
|
|
"hw monitor rate",
|
|
|
|
"hw2 monitor rate",
|
|
|
|
"raw rate",
|
|
|
|
"version",
|
|
|
|
"navigation settings",
|
|
|
|
"GNSS settings",
|
2016-10-16 21:56:34 -03:00
|
|
|
"SBAS settings",
|
2019-03-30 15:55:31 -03:00
|
|
|
"PVT rate",
|
2019-03-30 01:21:11 -03:00
|
|
|
"time pulse settings",
|
2019-11-13 16:18:14 -04:00
|
|
|
"TIMEGPS rate",
|
|
|
|
"Time mode settings"};
|
2016-04-12 00:16:20 -03:00
|
|
|
|
2019-03-30 15:55:31 -03:00
|
|
|
static_assert((1 << ARRAY_SIZE(reasons)) == CONFIG_LAST, "UBLOX: Missing configuration description");
|
2016-04-12 00:16:20 -03:00
|
|
|
|
|
|
|
void
|
|
|
|
AP_GPS_UBLOX::broadcast_configuration_failure_reason(void) const {
|
|
|
|
for (uint8_t i = 0; i < ARRAY_SIZE(reasons); i++) {
|
|
|
|
if (_unconfigured_messages & (1 << i)) {
|
2019-05-26 22:34:13 -03:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %u: u-blox %s configuration 0x%02x",
|
2019-07-26 23:06:48 -03:00
|
|
|
(unsigned int)(state.instance + 1), reasons[i], (unsigned int)_unconfigured_messages);
|
2016-04-12 00:16:20 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2016-12-18 19:31:28 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return velocity lag in seconds
|
|
|
|
*/
|
2017-05-24 14:42:03 -03:00
|
|
|
bool AP_GPS_UBLOX::get_lag(float &lag_sec) const
|
2016-12-18 19:31:28 -04:00
|
|
|
{
|
|
|
|
switch (_hardware_generation) {
|
2017-05-24 14:42:03 -03:00
|
|
|
case UBLOX_UNKNOWN_HARDWARE_GENERATION:
|
|
|
|
lag_sec = 0.22f;
|
|
|
|
// always bail out in this case, it's used to indicate we have yet to receive a valid
|
|
|
|
// hardware generation, however the user may have inhibited us detecting the generation
|
|
|
|
// so if we aren't allowed to do configuration, we will accept this as the default delay
|
2017-06-11 04:58:45 -03:00
|
|
|
return gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_ENABLE;
|
2016-12-18 19:31:28 -04:00
|
|
|
case UBLOX_5:
|
|
|
|
case UBLOX_6:
|
|
|
|
default:
|
2017-05-24 14:42:03 -03:00
|
|
|
lag_sec = 0.22f;
|
|
|
|
break;
|
2016-12-18 19:31:28 -04:00
|
|
|
case UBLOX_7:
|
|
|
|
case UBLOX_M8:
|
|
|
|
// based on flight logs the 7 and 8 series seem to produce about 120ms lag
|
2017-05-24 14:42:03 -03:00
|
|
|
lag_sec = 0.12f;
|
2016-12-18 19:31:28 -04:00
|
|
|
break;
|
2019-07-01 01:51:56 -03:00
|
|
|
case UBLOX_F9:
|
|
|
|
// F9 lag not verified yet from flight log, but likely to be at least
|
|
|
|
// as good as M8
|
|
|
|
lag_sec = 0.12f;
|
|
|
|
break;
|
2016-12-18 19:31:28 -04:00
|
|
|
};
|
2017-05-24 14:42:03 -03:00
|
|
|
return true;
|
2016-12-18 19:31:28 -04:00
|
|
|
}
|
2016-08-02 02:48:16 -03:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const
|
2016-08-02 02:48:16 -03:00
|
|
|
{
|
2019-05-26 22:34:13 -03:00
|
|
|
#ifndef HAL_NO_LOGGING
|
2019-01-18 00:23:42 -04:00
|
|
|
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
|
2016-08-02 02:48:16 -03:00
|
|
|
|
|
|
|
if (_have_version) {
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().Write_MessageF("u-blox %d HW: %s SW: %s",
|
2016-08-02 02:48:16 -03:00
|
|
|
state.instance+1,
|
|
|
|
_version.hwVersion,
|
|
|
|
_version.swVersion);
|
|
|
|
}
|
2019-05-26 22:34:13 -03:00
|
|
|
#endif
|
2016-08-02 02:48:16 -03:00
|
|
|
}
|
2018-05-15 22:16:01 -03:00
|
|
|
|
2018-06-19 19:35:41 -03:00
|
|
|
// uBlox specific check_new_itow(), handling message length
|
2018-05-15 22:16:01 -03:00
|
|
|
void AP_GPS_UBLOX::_check_new_itow(uint32_t itow)
|
|
|
|
{
|
2018-06-19 19:35:41 -03:00
|
|
|
check_new_itow(itow, _payload_length + sizeof(ubx_header) + 2);
|
2018-05-15 22:16:01 -03:00
|
|
|
}
|