From 50b736333f97761e4613354ee853071c652736ca Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 4 Feb 2013 15:57:12 +0100 Subject: [PATCH 01/20] Reduced, but functional u-blox series driver --- apps/drivers/drv_gps.h | 80 ++++ apps/drivers/gps/Makefile | 42 ++ apps/drivers/gps/gps.cpp | 627 ++++++++++++++++++++++++++ apps/drivers/gps/gps_helper.h | 47 ++ apps/drivers/gps/ubx.cpp | 818 ++++++++++++++++++++++++++++++++++ apps/drivers/gps/ubx.h | 369 +++++++++++++++ 6 files changed, 1983 insertions(+) create mode 100644 apps/drivers/drv_gps.h create mode 100644 apps/drivers/gps/Makefile create mode 100644 apps/drivers/gps/gps.cpp create mode 100644 apps/drivers/gps/gps_helper.h create mode 100644 apps/drivers/gps/ubx.cpp create mode 100644 apps/drivers/gps/ubx.h diff --git a/apps/drivers/drv_gps.h b/apps/drivers/drv_gps.h new file mode 100644 index 0000000000..89fc54b0d9 --- /dev/null +++ b/apps/drivers/drv_gps.h @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file GPS driver interface. + */ + +#ifndef _DRV_GPS_H +#define _DRV_GPS_H + +#include +#include + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define GPS_DEVICE_PATH "/dev/gps" + +typedef enum { + GPS_DRIVER_MODE_UBX = 0, + GPS_DRIVER_MODE_MTK19, + GPS_DRIVER_MODE_MTK16, + GPS_DRIVER_MODE_NMEA, +} gps_driver_mode_t; + + + + +/* + * ObjDev tag for GPS data. + */ +ORB_DECLARE(gps); + +/* + * ioctl() definitions + */ +#define _GPSIOCBASE (0x2800) //TODO: arbitrary choice... +#define _GPSIOC(_n) (_IOC(_GPSIOCBASE, _n)) + +/** configure ubx mode */ +#define GPS_CONFIGURE_UBX _GPSIOC(0) + +/** configure mtk mode */ +#define GPS_CONFIGURE_MTK19 _GPSIOC(1) +#define GPS_CONFIGURE_MTK16 _GPSIOC(2) + +/** configure mtk mode */ +#define GPS_CONFIGURE_NMEA _GPSIOC(3) + +#endif /* _DRV_GPS_H */ diff --git a/apps/drivers/gps/Makefile b/apps/drivers/gps/Makefile new file mode 100644 index 0000000000..3859a88a5a --- /dev/null +++ b/apps/drivers/gps/Makefile @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# GPS driver +# + +APPNAME = gps +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +include $(APPDIR)/mk/app.mk diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp new file mode 100644 index 0000000000..7d6f7144ef --- /dev/null +++ b/apps/drivers/gps/gps.cpp @@ -0,0 +1,627 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file gps.cpp + * Driver for the GPS on UART6 + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include + +#include +#include +#include + +#include + +#include + +#include "ubx.h" + +#define SEND_BUFFER_LENGTH 100 +#define TIMEOUT 1000000 //1s + +#define NUMBER_OF_BAUDRATES 4 +#define CONFIG_TIMEOUT 2000000 + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + +#ifndef CONFIG_SCHED_WORKQUEUE +# error This requires CONFIG_SCHED_WORKQUEUE. +#endif + + + +class GPS : public device::CDev +{ +public: + GPS(); + ~GPS(); + + virtual int init(); + + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + + /** + * Diagnostics - print some basic information about the driver. + */ + void print_info(); + +private: + + int _task_should_exit; + int _serial_fd; ///< serial interface to GPS + unsigned _baudrate; + unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; + uint8_t _send_buffer[SEND_BUFFER_LENGTH]; + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; + perf_counter_t _buffer_overflows; + volatile int _task; ///< worker task + + bool _response_received; + bool _config_needed; + bool _baudrate_changed; + bool _mode_changed; + bool _healthy; + gps_driver_mode_t _mode; + unsigned _messages_received; + + GPS_Helper *_Helper; ///< Class for either UBX, MTK or NMEA helper + + struct vehicle_gps_position_s _report; + orb_advert_t _report_pub; + + orb_advert_t _gps_topic; + + void recv(); + + void config(); + + static void task_main_trampoline(void *arg); + + + /** + * worker task + */ + void task_main(void); + + int set_baudrate(unsigned baud); + + /** + * Send a reset command to the GPS + */ + void cmd_reset(); + +}; + + +/* + * Driver 'main' command. + */ +extern "C" __EXPORT int gps_main(int argc, char *argv[]); + +namespace +{ + +GPS *g_dev; + +} + + +GPS::GPS() : + CDev("gps", GPS_DEVICE_PATH), + _task_should_exit(false), + _baudrates_to_try({9600, 38400, 57600, 115200}), + _config_needed(true), + _baudrate_changed(false), + _mode_changed(true), + _healthy(false), + _mode(GPS_DRIVER_MODE_UBX), + _messages_received(0), + _Helper(nullptr) +{ + /* we need this potentially before it could be set in task_main */ + g_dev = this; + + _debug_enabled = true; + debug("[gps driver] instantiated"); +} + +GPS::~GPS() +{ + /* tell the task we want it to go away */ + _task_should_exit = true; + + /* spin waiting for the task to stop */ + for (unsigned i = 0; (i < 10) && (_task != -1); i++) { + /* give it another 100ms */ + usleep(100000); + } + + /* well, kill it anyway, though this will probably crash */ + if (_task != -1) + task_delete(_task); + g_dev = nullptr; +} + +int +GPS::init() +{ + int ret = ERROR; + + /* do regular cdev init */ + if (CDev::init() != OK) + goto out; + + /* start the IO interface task */ + _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 4096, (main_t)&GPS::task_main_trampoline, nullptr); + + if (_task < 0) { + debug("task start failed: %d", errno); + return -errno; + } + +// if (_gps_topic < 0) +// debug("failed to create GPS object"); + + ret = OK; +out: + return ret; +} + +int +GPS::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + int ret = OK; + + switch (cmd) { + case GPS_CONFIGURE_UBX: + if (_mode != GPS_DRIVER_MODE_UBX) { + _mode = GPS_DRIVER_MODE_UBX; + _mode_changed = true; + } + break; + case GPS_CONFIGURE_MTK19: + if (_mode != GPS_DRIVER_MODE_MTK19) { + _mode = GPS_DRIVER_MODE_MTK19; + _mode_changed = true; + } + break; + case GPS_CONFIGURE_MTK16: + if (_mode != GPS_DRIVER_MODE_MTK16) { + _mode = GPS_DRIVER_MODE_MTK16; + _mode_changed = true; + } + break; + case GPS_CONFIGURE_NMEA: + if (_mode != GPS_DRIVER_MODE_NMEA) { + _mode = GPS_DRIVER_MODE_NMEA; + _mode_changed = true; + } + break; + case SENSORIOCRESET: + cmd_reset(); + break; + } + + return ret; +} + +void +GPS::config() +{ + int length = 0; + + _Helper->configure(_config_needed, _baudrate_changed, _baudrate, _send_buffer, length, SEND_BUFFER_LENGTH); + + /* the message needs to be sent at the old baudrate */ + if (length > 0) { + if (length != ::write(_serial_fd, _send_buffer, length)) { + debug("write config failed"); + return; + } + } + + if (_baudrate_changed) { + set_baudrate(_baudrate); + _baudrate_changed = false; + } +} + +void +GPS::task_main_trampoline(void *arg) +{ + g_dev->task_main(); +} + +void +GPS::task_main() +{ + log("starting"); + + _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + + memset(&_report, 0, sizeof(_report)); + + /* open the serial port */ + _serial_fd = ::open("/dev/ttyS3", O_RDWR); + + uint8_t buf[256]; + int baud_i = 0; + uint64_t time_before_configuration; + + if (_serial_fd < 0) { + log("failed to open serial port: %d", errno); + goto out; + } + + /* poll descriptor */ + pollfd fds[1]; + fds[0].fd = _serial_fd; + fds[0].events = POLLIN; + debug("ready"); + + /* lock against the ioctl handler */ + lock(); + + + _baudrate = _baudrates_to_try[baud_i]; + set_baudrate(_baudrate); + + time_before_configuration = hrt_absolute_time(); + + /* loop handling received serial bytes */ + while (!_task_should_exit) { + + if (_mode_changed) { + if (_Helper != nullptr) { + delete(_Helper); + _Helper = nullptr; // XXX is this needed? + } + + switch (_mode) { + case GPS_DRIVER_MODE_UBX: + _Helper = new UBX(); + break; + case GPS_DRIVER_MODE_MTK19: + //_Helper = new MTK19(); + break; + case GPS_DRIVER_MODE_MTK16: + //_Helper = new MTK16(); + break; + case GPS_DRIVER_MODE_NMEA: + //_Helper = new NMEA(); + break; + default: + break; + } + _mode_changed = false; + } + + if (_config_needed && time_before_configuration + CONFIG_TIMEOUT < hrt_absolute_time()) { + baud_i = (baud_i+1)%NUMBER_OF_BAUDRATES; + _baudrate = _baudrates_to_try[baud_i]; + set_baudrate(_baudrate); + time_before_configuration = hrt_absolute_time(); + } + + + int poll_timeout; + if (_config_needed) { + poll_timeout = 50; + } else { + poll_timeout = 250; + } + /* sleep waiting for data, but no more than 1000ms */ + unlock(); + int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), poll_timeout); + lock(); + + + + + /* this would be bad... */ + if (ret < 0) { + log("poll error %d", errno); + } else if (ret == 0) { + config(); + if (_config_needed == false) { + _config_needed = true; + debug("Lost GPS module"); + } + } else if (ret > 0) { + /* if we have new data from GPS, go handle it */ + if (fds[0].revents & POLLIN) { + int count; + + /* + * We are here because poll says there is some data, so this + * won't block even on a blocking device. If more bytes are + * available, we'll go back to poll() again... + */ + count = ::read(_serial_fd, buf, sizeof(buf)); + + /* pass received bytes to the packet decoder */ + int j; + for (j = 0; j < count; j++) { + _messages_received += _Helper->parse(buf[j], &_report); + } + if (_messages_received > 0) { + if (_config_needed == true) { + _config_needed = false; + debug("Found GPS module"); + } + + orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + _messages_received = 0; + } + } + } + } +out: + debug("exiting"); + + ::close(_serial_fd); + + /* tell the dtor that we are exiting */ + _task = -1; + _exit(0); +} + +int +GPS::set_baudrate(unsigned baud) +{ + /* process baud rate */ + int speed; + + switch (baud) { + case 9600: speed = B9600; break; + + case 19200: speed = B19200; break; + + case 38400: speed = B38400; break; + + case 57600: speed = B57600; break; + + case 115200: speed = B115200; break; + + default: + warnx("ERROR: Unsupported baudrate: %d\n", baud); + return -EINVAL; + } + + struct termios uart_config; + int termios_state; + + /* fill the struct for the new configuration */ + tcgetattr(_serial_fd, &uart_config); + + /* clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + /* no parity, one stop bit */ + uart_config.c_cflag &= ~(CSTOPB | PARENB); + + /* set baud rate */ + if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { + warnx("ERROR setting config: %d (cfsetispeed, cfsetospeed)\n", termios_state); + return -1; + } + + + if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) { + warnx("ERROR setting baudrate (tcsetattr)\n"); + return -1; + } +} + +void +GPS::cmd_reset() +{ + _healthy = false; +} + +void +GPS::print_info() +{ + +} + +/** + * Local functions in support of the shell command. + */ +namespace gps +{ + +GPS *g_dev; + +void start(); +void stop(); +void test(); +void reset(); +void info(); + +/** + * Start the driver. + */ +void +start() +{ + int fd; + + if (g_dev != nullptr) + errx(1, "already started"); + + /* create the driver */ + g_dev = new GPS; + + if (g_dev == nullptr) + goto fail; + + if (OK != g_dev->init()) + goto fail; + + /* set the poll rate to default, starts automatic data collection */ + fd = open(GPS_DEVICE_PATH, O_RDONLY); + + if (fd < 0) { + printf("Could not open device path: %s\n", GPS_DEVICE_PATH); + goto fail; + } + exit(0); + +fail: + + if (g_dev != nullptr) { + delete g_dev; + g_dev = nullptr; + } + + errx(1, "driver start failed"); +} + +void +stop() +{ + delete g_dev; + g_dev = nullptr; + + exit(0); +} + +/** + * Perform some basic functional tests on the driver; + * make sure we can collect data from the sensor in polled + * and automatic modes. + */ +void +test() +{ + + errx(0, "PASS"); +} + +/** + * Reset the driver. + */ +void +reset() +{ + int fd = open(GPS_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + err(1, "failed "); + + if (ioctl(fd, SENSORIOCRESET, 0) < 0) + err(1, "driver reset failed"); + + exit(0); +} + +/** + * Print the status of the driver. + */ +void +info() +{ + if (g_dev == nullptr) + errx(1, "driver not running"); + + printf("state @ %p\n", g_dev); + g_dev->print_info(); + + exit(0); +} + +} // namespace + + +int +gps_main(int argc, char *argv[]) +{ + /* + * Start/load the driver. + */ + if (!strcmp(argv[1], "start")) + gps::start(); + + if (!strcmp(argv[1], "stop")) + gps::stop(); + /* + * Test the driver/device. + */ + if (!strcmp(argv[1], "test")) + gps::test(); + + /* + * Reset the driver. + */ + if (!strcmp(argv[1], "reset")) + gps::reset(); + + /* + * Print driver status. + */ + if (!strcmp(argv[1], "status")) + gps::info(); + + errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status'"); +} diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h new file mode 100644 index 0000000000..baacf7cb47 --- /dev/null +++ b/apps/drivers/gps/gps_helper.h @@ -0,0 +1,47 @@ +/**************************************************************************** + * + * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. + * Author: Thomas Gubler + * Julian Oes + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* @file U-Blox protocol definitions */ + +#ifndef GPS_HELPER_H + +class GPS_Helper +{ +public: + virtual void configure(bool&, bool&, unsigned&, uint8_t*, int&, const unsigned) = 0; + virtual int parse(uint8_t, struct vehicle_gps_position_s*) = 0; +}; + +#endif /* GPS_HELPER_H */ diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp new file mode 100644 index 0000000000..981b023e55 --- /dev/null +++ b/apps/drivers/gps/ubx.cpp @@ -0,0 +1,818 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Author: Thomas Gubler + * Julian Oes + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* @file U-Blox protocol implementation */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ubx.h" + + +UBX::UBX() : +_waited(0), +_config_state(UBX_CONFIG_STATE_PRT), +_new_nav_posllh(false), +_new_nav_timeutc(false), +_new_nav_dop(false), +_new_nav_sol(false), +_new_nav_velned(false) +{ + decodeInit(); + _waiting_for_ack = false; +} + +UBX::~UBX() +{ +} + +void +UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, uint8_t *buffer, int &length, const unsigned max_length) +{ + /* make sure the buffer to write the message is long enough */ + assert(sizeof(type_gps_bin_cfg_prt_packet_t)+2 <= max_length); + + /* try again after 10 times */ + if (_waited > 10) { + _waiting_for_ack = false; + } + + if (!_waiting_for_ack) { + _waiting_for_ack = true; + _waited = 0; + if (_config_state == UBX_CONFIG_STATE_CONFIGURED) { + config_needed = false; + length = 0; + _config_state = UBX_CONFIG_STATE_PRT; /* set the state for next time */ + _waiting_for_ack = false; + return; + } else if (_config_state == UBX_CONFIG_STATE_PRT) { + /* send a CFT-PRT message to define set ubx protocol and leave the baudrate as is, we just want an ACK-ACK from this */ + type_gps_bin_cfg_prt_packet_t cfg_prt_packet; + memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); + + cfg_prt_packet.clsID = UBX_CLASS_CFG; + cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; + cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; + cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; + cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; + cfg_prt_packet.baudRate = baudrate; + cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; + cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; + + addChecksumToMessage((uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); + + buffer[0] = UBX_SYNC1; + buffer[1] = UBX_SYNC2; + memcpy(&(buffer[2]), &cfg_prt_packet, sizeof(cfg_prt_packet)); + length = sizeof(cfg_prt_packet)+2; + + } else if (_config_state == UBX_CONFIG_STATE_PRT_NEW_BAUDRATE) { + +// printf("Send change of baudrate now\n"); + + /* send a CFT-PRT message to define set ubx protocol and and baudrate, now let's try to switch the baudrate */ + type_gps_bin_cfg_prt_packet_t cfg_prt_packet; + memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); + + cfg_prt_packet.clsID = UBX_CLASS_CFG; + cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; + cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; + cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; + cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; + cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE; + cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; + cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; + + addChecksumToMessage((uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); + + buffer[0] = UBX_SYNC1; + buffer[1] = UBX_SYNC2; + memcpy(&(buffer[2]), &cfg_prt_packet, sizeof(cfg_prt_packet)); + length = sizeof(cfg_prt_packet)+2; + + /* detection when the baudrate has been changed in the first step */ + if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) { + /* set a flag and exit */ + baudrate=UBX_CFG_PRT_PAYLOAD_BAUDRATE; + baudrate_changed = true; + _config_state = UBX_CONFIG_STATE_RATE; + _waiting_for_ack = false; + return; + } + + + + } else if (_config_state == UBX_CONFIG_STATE_RATE) { + + /* send a CFT-RATE message to define update rate */ + type_gps_bin_cfg_rate_packet_t cfg_rate_packet; + memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet)); + + cfg_rate_packet.clsID = UBX_CLASS_CFG; + cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE; + cfg_rate_packet.length = UBX_CFG_RATE_LENGTH; + cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASRATE; + cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE; + cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF; + + addChecksumToMessage((uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet)); + + buffer[0] = UBX_SYNC1; + buffer[1] = UBX_SYNC2; + memcpy(&(buffer[2]), &cfg_rate_packet, sizeof(cfg_rate_packet)); + length = sizeof(cfg_rate_packet)+2; + + } else if (_config_state == UBX_CONFIG_STATE_NAV5) { + /* send a NAV5 message to set the options for the internal estimator */ + type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet; + memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet)); //set everything to 0 + + cfg_nav5_packet.clsID = UBX_CLASS_CFG; + cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5; + cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH; + cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK; + cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL; + cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE; + + addChecksumToMessage((uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet)); + + buffer[0] = UBX_SYNC1; + buffer[1] = UBX_SYNC2; + memcpy(&(buffer[2]), &cfg_nav5_packet, sizeof(cfg_nav5_packet)); + length = sizeof(cfg_nav5_packet)+2; + + } else { + /* catch the remaining config states here */ + + type_gps_bin_cfg_msg_packet_t cfg_msg_packet; + memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet)); //set everything to 0 + + cfg_msg_packet.clsID = UBX_CLASS_CFG; + cfg_msg_packet.msgID = UBX_MESSAGE_CFG_MSG; + cfg_msg_packet.length = UBX_CFG_MSG_LENGTH; + cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1; + + switch (_config_state) { + case UBX_CONFIG_STATE_MSG_NAV_POSLLH: + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_POSLLH; + break; + case UBX_CONFIG_STATE_MSG_NAV_TIMEUTC: + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC; + break; + case UBX_CONFIG_STATE_MSG_NAV_DOP: + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP; + break; + case UBX_CONFIG_STATE_MSG_NAV_SVINFO: + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO; + cfg_msg_packet.rate[1] = 5; + break; + case UBX_CONFIG_STATE_MSG_NAV_SOL: + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SOL; + break; + case UBX_CONFIG_STATE_MSG_NAV_VELNED: + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_VELNED; + break; +// case UBX_CONFIG_STATE_MSG_RXM_SVSI: +// cfg_msg_packet.msgClass_payload = UBX_CLASS_RXM; +// cfg_msg_packet.msgID_payload = UBX_MESSAGE_RXM_SVSI; +// break; + default: + break; + } + + addChecksumToMessage((uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); + + buffer[0] = UBX_SYNC1; + buffer[1] = UBX_SYNC2; + memcpy(&(buffer[2]), &cfg_msg_packet, sizeof(cfg_msg_packet)); + length = sizeof(cfg_msg_packet)+2; + } + } else { + _waited++; + } +} + +int +UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) +{ + int ret = 0; + //printf("Received char: %c\n", b); + + switch (_decode_state) { + /* First, look for sync1 */ + case UBX_DECODE_UNINIT: + if (b == UBX_SYNC1) { + _decode_state = UBX_DECODE_GOT_SYNC1; + } + break; + /* Second, look for sync2 */ + case UBX_DECODE_GOT_SYNC1: + if (b == UBX_SYNC2) { + _decode_state = UBX_DECODE_GOT_SYNC2; + } else { + /* Second start symbol was wrong, reset state machine */ + decodeInit(); + } + break; + /* Now look for class */ + case UBX_DECODE_GOT_SYNC2: + /* everything except sync1 and sync2 needs to be added to the checksum */ + addByteToChecksum(b); + /* check for known class */ + switch (b) { + case UBX_CLASS_ACK: + _decode_state = UBX_DECODE_GOT_CLASS; + _message_class = ACK; + break; + + case UBX_CLASS_NAV: + _decode_state = UBX_DECODE_GOT_CLASS; + _message_class = NAV; + break; + +// case UBX_CLASS_RXM: +// _decode_state = UBX_DECODE_GOT_CLASS; +// _message_class = RXM; +// break; + + case UBX_CLASS_CFG: + _decode_state = UBX_DECODE_GOT_CLASS; + _message_class = CFG; + break; + default: //unknown class: reset state machine + decodeInit(); + break; + } + break; + case UBX_DECODE_GOT_CLASS: + addByteToChecksum(b); + switch (_message_class) { + case NAV: + switch (b) { + case UBX_MESSAGE_NAV_POSLLH: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = NAV_POSLLH; + break; + + case UBX_MESSAGE_NAV_SOL: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = NAV_SOL; + break; + + case UBX_MESSAGE_NAV_TIMEUTC: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = NAV_TIMEUTC; + break; + + case UBX_MESSAGE_NAV_DOP: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = NAV_DOP; + break; + + case UBX_MESSAGE_NAV_SVINFO: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = NAV_SVINFO; + break; + + case UBX_MESSAGE_NAV_VELNED: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = NAV_VELNED; + break; + + default: //unknown class: reset state machine, should not happen + decodeInit(); + break; + } + break; +// case RXM: +// switch (b) { +// case UBX_MESSAGE_RXM_SVSI: +// _decode_state = UBX_DECODE_GOT_MESSAGEID; +// _message_id = RXM_SVSI; +// break; +// +// default: //unknown class: reset state machine, should not happen +// decodeInit(); +// break; +// } +// break; + + case CFG: + switch (b) { + case UBX_MESSAGE_CFG_NAV5: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = CFG_NAV5; + break; + + default: //unknown class: reset state machine, should not happen + decodeInit(); + break; + } + break; + + case ACK: + switch (b) { + case UBX_MESSAGE_ACK_ACK: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = ACK_ACK; + break; + case UBX_MESSAGE_ACK_NAK: + _decode_state = UBX_DECODE_GOT_MESSAGEID; + _message_id = ACK_NAK; + break; + default: //unknown class: reset state machine, should not happen + decodeInit(); + break; + } + break; + default: //should not happen because we set the class + printf("UBX Error, we set a class that we don't know\n"); + decodeInit(); + break; + } + break; + case UBX_DECODE_GOT_MESSAGEID: + addByteToChecksum(b); + _payload_size = b; //this is the first length byte + _decode_state = UBX_DECODE_GOT_LENGTH1; + break; + case UBX_DECODE_GOT_LENGTH1: + addByteToChecksum(b); + _payload_size += b << 8; // here comes the second byte of length + _decode_state = UBX_DECODE_GOT_LENGTH2; + break; + case UBX_DECODE_GOT_LENGTH2: + /* Add to checksum if not yet at checksum byte */ + if (_rx_count < _payload_size) + addByteToChecksum(b); + _rx_buffer[_rx_count] = b; + /* once the payload has arrived, we can process the information */ + if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes + switch (_message_id) { //this enum is unique for all ids --> no need to check the class + case NAV_POSLLH: { +// printf("GOT NAV_POSLLH MESSAGE\n"); + gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer; + + //Check if checksum is valid and the store the gps information + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + gps_position->lat = packet->lat; + gps_position->lon = packet->lon; + gps_position->alt = packet->height_msl; + + gps_position->counter_pos_valid++; + gps_position->counter++; + + _new_nav_posllh = true; + + } else { + printf("[gps] NAV_POSLLH: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + + case NAV_SOL: { +// printf("GOT NAV_SOL MESSAGE\n"); + gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer; + + //Check if checksum is valid and the store the gps information + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + + gps_position->fix_type = packet->gpsFix; + + gps_position->timestamp = hrt_absolute_time(); + gps_position->counter++; + gps_position->s_variance = packet->sAcc; + gps_position->p_variance = packet->pAcc; + + _new_nav_sol = true; + + } else { + printf("[gps] NAV_SOL: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + + case NAV_DOP: { +// printf("GOT NAV_DOP MESSAGE\n"); + gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer; + + //Check if checksum is valid and the store the gps information + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + + gps_position->eph = packet->hDOP; + gps_position->epv = packet->vDOP; + + gps_position->timestamp = hrt_absolute_time(); + gps_position->counter++; + + _new_nav_dop = true; + + } else { + printf("[gps] NAV_DOP: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + + case NAV_TIMEUTC: { +// printf("GOT NAV_TIMEUTC MESSAGE\n"); + gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer; + + //Check if checksum is valid and the store the gps information + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + //convert to unix timestamp + struct tm timeinfo; + timeinfo.tm_year = packet->year - 1900; + timeinfo.tm_mon = packet->month - 1; + timeinfo.tm_mday = packet->day; + timeinfo.tm_hour = packet->hour; + timeinfo.tm_min = packet->min; + timeinfo.tm_sec = packet->sec; + + time_t epoch = mktime(&timeinfo); + + gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this + gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); + + gps_position->timestamp = hrt_absolute_time(); + gps_position->counter++; + + _new_nav_timeutc = true; + + } else { + printf("\t[gps] NAV_TIMEUTC: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + + case NAV_SVINFO: { +// printf("GOT NAV_SVINFO MESSAGE\n"); + + //this is a more complicated message: the length depends on the number of satellites. This number is extracted from the first part of the message + const int length_part1 = 8; + char _rx_buffer_part1[length_part1]; + memcpy(_rx_buffer_part1, _rx_buffer, length_part1); + gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer_part1; + + //read checksum + const int length_part3 = 2; + char _rx_buffer_part3[length_part3]; + memcpy(_rx_buffer_part3, &(_rx_buffer[_rx_count - 1]), length_part3); + gps_bin_nav_svinfo_part3_packet_t *packet_part3 = (gps_bin_nav_svinfo_part3_packet_t *) _rx_buffer_part3; + + //Check if checksum is valid and then store the gps information + if (_rx_ck_a == packet_part3->ck_a && _rx_ck_b == packet_part3->ck_b) { + //definitions needed to read numCh elements from the buffer: + const int length_part2 = 12; + gps_bin_nav_svinfo_part2_packet_t *packet_part2; + char _rx_buffer_part2[length_part2]; //for temporal storage + + uint8_t satellites_used = 0; + int i; + + for (i = 0; i < packet_part1->numCh; i++) { //for each channel + + /* Get satellite information from the buffer */ + memcpy(_rx_buffer_part2, &(_rx_buffer[length_part1 + i * length_part2]), length_part2); + packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) _rx_buffer_part2; + + + /* Write satellite information in the global storage */ + gps_position->satellite_prn[i] = packet_part2->svid; + + //if satellite information is healthy store the data + uint8_t unhealthy = packet_part2->flags & 1 << 4; //flags is a bitfield + + if (!unhealthy) { + if ((packet_part2->flags) & 1) { //flags is a bitfield + gps_position->satellite_used[i] = 1; + satellites_used++; + + } else { + gps_position->satellite_used[i] = 0; + } + + gps_position->satellite_snr[i] = packet_part2->cno; + gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev); + gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f); + + } else { + gps_position->satellite_used[i] = 0; + gps_position->satellite_snr[i] = 0; + gps_position->satellite_elevation[i] = 0; + gps_position->satellite_azimuth[i] = 0; + } + + } + + for (i = packet_part1->numCh; i < 20; i++) { //these channels are unused + /* Unused channels have to be set to zero for e.g. MAVLink */ + gps_position->satellite_prn[i] = 0; + gps_position->satellite_used[i] = 0; + gps_position->satellite_snr[i] = 0; + gps_position->satellite_elevation[i] = 0; + gps_position->satellite_azimuth[i] = 0; + } + + /* set flag if any sat info is available */ + if (!packet_part1->numCh > 0) { + gps_position->satellite_info_available = 1; + + } else { + gps_position->satellite_info_available = 0; + } + + gps_position->satellites_visible = satellites_used++; // visible ~= used but we are interested in the used ones + gps_position->timestamp = hrt_absolute_time(); + gps_position->counter++; + + // as this message arrives only with 1Hz and is not essential, we don't take it into account for the report + + } else { + printf("\t[gps] NAV_SVINFO: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + + case NAV_VELNED: { +// printf("GOT NAV_VELNED MESSAGE\n"); + gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer; + + //Check if checksum is valid and the store the gps information + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + + gps_position->vel = (uint16_t)packet->speed; + gps_position->vel_n = packet->velN / 100.0f; + gps_position->vel_e = packet->velE / 100.0f; + gps_position->vel_d = packet->velD / 100.0f; + gps_position->vel_ned_valid = true; + gps_position->cog = (uint16_t)((float)(packet->heading) * 1e-3f); + + gps_position->timestamp = hrt_absolute_time(); + gps_position->counter++; + + + _new_nav_velned = true; + + } else { + printf("[gps] NAV_VELNED: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + +// case RXM_SVSI: { +// printf("GOT RXM_SVSI MESSAGE\n"); +// const int length_part1 = 7; +// char _rx_buffer_part1[length_part1]; +// memcpy(_rx_buffer_part1, _rx_buffer, length_part1); +// gps_bin_rxm_svsi_packet_t *packet = (gps_bin_rxm_svsi_packet_t *) _rx_buffer_part1; +// +// //Check if checksum is valid and the store the gps information +// if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) { +// +// gps_position->satellites_visible = packet->numVis; +// gps_position->timestamp = hrt_absolute_time(); +// gps_position->counter++; +// _last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time(); +// ret = 1; +// +// } else { +// printf("[gps] RXM_SVSI: checksum invalid\n"); +// } +// +// // Reset state machine to decode next packet +// decodeInit(); +// return ret; +// +// break; +// } + + case ACK_ACK: { +// printf("GOT ACK_ACK\n"); + gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer; + + //Check if checksum is valid + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + + _waiting_for_ack = false; + + switch (_config_state) { + case UBX_CONFIG_STATE_PRT: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_PRT) + _config_state = UBX_CONFIG_STATE_PRT_NEW_BAUDRATE; + break; + case UBX_CONFIG_STATE_PRT_NEW_BAUDRATE: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_PRT) + _config_state = UBX_CONFIG_STATE_RATE; + break; + case UBX_CONFIG_STATE_RATE: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_RATE) + _config_state = UBX_CONFIG_STATE_NAV5; + break; + case UBX_CONFIG_STATE_NAV5: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_NAV5) + _config_state = UBX_CONFIG_STATE_MSG_NAV_POSLLH; + break; + case UBX_CONFIG_STATE_MSG_NAV_POSLLH: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) + _config_state = UBX_CONFIG_STATE_MSG_NAV_TIMEUTC; + break; + case UBX_CONFIG_STATE_MSG_NAV_TIMEUTC: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) + _config_state = UBX_CONFIG_STATE_MSG_NAV_DOP; + break; + case UBX_CONFIG_STATE_MSG_NAV_DOP: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) + _config_state = UBX_CONFIG_STATE_MSG_NAV_SVINFO; + break; + case UBX_CONFIG_STATE_MSG_NAV_SVINFO: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) + _config_state = UBX_CONFIG_STATE_MSG_NAV_SOL; + break; + case UBX_CONFIG_STATE_MSG_NAV_SOL: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) + _config_state = UBX_CONFIG_STATE_MSG_NAV_VELNED; + break; + case UBX_CONFIG_STATE_MSG_NAV_VELNED: + if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) + _config_state = UBX_CONFIG_STATE_CONFIGURED; + break; +// case UBX_CONFIG_STATE_MSG_RXM_SVSI: +// if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) +// _config_state = UBX_CONFIG_STATE_CONFIGURED; +// break; + default: + break; + } + } else { + printf("[gps] ACK_ACK: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + + case ACK_NAK: { +// printf("GOT ACK_NAK\n"); + gps_bin_ack_nak_packet_t *packet = (gps_bin_ack_nak_packet_t *) _rx_buffer; + + //Check if checksum is valid + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + + printf("[gps] the ubx gps returned: not acknowledged\n"); + ret = 1; + + } else { + printf("[gps] ACK_NAK: checksum invalid\n"); + } + + // Reset state machine to decode next packet + decodeInit(); + return ret; + + break; + } + + default: //we don't know the message + printf("Unknown message received: %d-%d\n",_message_class,_message_id); + decodeInit(); + + break; + } + } // end if _rx_count high enough + if (_rx_count < RECV_BUFFER_SIZE) { + _rx_count++; + } else { + printf("Buffer full"); + decodeInit(); + } + break; + default: + break; + } + + /* return 1 when all needed messages have arrived */ + if(_new_nav_posllh &&_new_nav_timeutc && _new_nav_dop && _new_nav_sol && _new_nav_velned) { + + gps_position->timestamp = hrt_absolute_time(); + ret = 1; + _new_nav_posllh = false; + _new_nav_timeutc = false; + _new_nav_dop = false; + _new_nav_sol = false; + _new_nav_velned = false; + } + + return ret; +} + +void +UBX::decodeInit(void) +{ + _rx_ck_a = 0; + _rx_ck_b = 0; + _rx_count = 0; + _decode_state = UBX_DECODE_UNINIT; + _message_class = CLASS_UNKNOWN; + _message_id = ID_UNKNOWN; + _payload_size = 0; +} + +void +UBX::addByteToChecksum(uint8_t b) +{ + _rx_ck_a = _rx_ck_a + b; + _rx_ck_b = _rx_ck_b + _rx_ck_a; +} + +void +UBX::addChecksumToMessage(uint8_t* message, const unsigned length) +{ + uint8_t ck_a = 0; + uint8_t ck_b = 0; + unsigned i; + + for (i = 0; i < length-2; i++) { + ck_a = ck_a + message[i]; + ck_b = ck_b + ck_a; + } + message[length-2] = ck_a; + message[length-1] = ck_b; +} diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h new file mode 100644 index 0000000000..dff25a518f --- /dev/null +++ b/apps/drivers/gps/ubx.h @@ -0,0 +1,369 @@ +/**************************************************************************** + * + * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. + * Author: Thomas Gubler + * Julian Oes + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* @file U-Blox protocol definitions */ + +#ifndef UBX_H_ +#define UBX_H_ + +#include "gps_helper.h" + +#define UBX_NO_OF_MESSAGES 7 /**< Read 7 UBX GPS messages */ + +#define UBX_SYNC1 0xB5 +#define UBX_SYNC2 0x62 + +//UBX Protocol definitions (this is the subset of the messages that are parsed) +#define UBX_CLASS_NAV 0x01 +//#define UBX_CLASS_RXM 0x02 +#define UBX_CLASS_ACK 0x05 +#define UBX_CLASS_CFG 0x06 +#define UBX_MESSAGE_NAV_POSLLH 0x02 +#define UBX_MESSAGE_NAV_SOL 0x06 +#define UBX_MESSAGE_NAV_TIMEUTC 0x21 +#define UBX_MESSAGE_NAV_DOP 0x04 +#define UBX_MESSAGE_NAV_SVINFO 0x30 +#define UBX_MESSAGE_NAV_VELNED 0x12 +//#define UBX_MESSAGE_RXM_SVSI 0x20 +#define UBX_MESSAGE_ACK_ACK 0x01 +#define UBX_MESSAGE_ACK_NAK 0x00 +#define UBX_MESSAGE_CFG_PRT 0x00 +#define UBX_MESSAGE_CFG_NAV5 0x24 +#define UBX_MESSAGE_CFG_MSG 0x01 +#define UBX_MESSAGE_CFG_RATE 0x08 + +#define UBX_CFG_PRT_LENGTH 20 +#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< port 1 */ +#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ +#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */ +#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< ubx in */ +#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< ubx out */ + +#define UBX_CFG_RATE_LENGTH 6 +#define UBX_CFG_RATE_PAYLOAD_MEASRATE 200 /**< 200ms for 5Hz */ +#define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */ +#define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */ + + +#define UBX_CFG_NAV5_LENGTH 36 +#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0001 /**< only update dynamic model and fix mode */ +#define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */ +#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */ + +#define UBX_CFG_MSG_LENGTH 8 +#define UBX_CFG_MSG_PAYLOAD_RATE1 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} UART1 chosen */ + + +// ************ +/** the structures of the binary packets */ +#pragma pack(push, 1) + +typedef struct { + uint32_t time_milliseconds; // GPS Millisecond Time of Week + int32_t lon; // Longitude * 1e-7, deg + int32_t lat; // Latitude * 1e-7, deg + int32_t height; // Height above Ellipsoid, mm + int32_t height_msl; // Height above mean sea level, mm + uint32_t hAcc; // Horizontal Accuracy Estimate, mm + uint32_t vAcc; // Vertical Accuracy Estimate, mm + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_nav_posllh_packet_t; + +typedef struct { + uint32_t time_milliseconds; // GPS Millisecond Time of Week + int32_t time_nanoseconds; // Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 + int16_t week; // GPS week (GPS time) + uint8_t gpsFix; //GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix + uint8_t flags; + int32_t ecefX; + int32_t ecefY; + int32_t ecefZ; + uint32_t pAcc; + int32_t ecefVX; + int32_t ecefVY; + int32_t ecefVZ; + uint32_t sAcc; + uint16_t pDOP; + uint8_t reserved1; + uint8_t numSV; + uint32_t reserved2; + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_nav_sol_packet_t; + +typedef struct { + uint32_t time_milliseconds; // GPS Millisecond Time of Week + uint32_t time_accuracy; //Time Accuracy Estimate, ns + int32_t time_nanoseconds; //Nanoseconds of second, range -1e9 .. 1e9 (UTC) + uint16_t year; //Year, range 1999..2099 (UTC) + uint8_t month; //Month, range 1..12 (UTC) + uint8_t day; //Day of Month, range 1..31 (UTC) + uint8_t hour; //Hour of Day, range 0..23 (UTC) + uint8_t min; //Minute of Hour, range 0..59 (UTC) + uint8_t sec; //Seconds of Minute, range 0..59 (UTC) + uint8_t valid_flag; //Validity Flags (see ubx documentation) + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_nav_timeutc_packet_t; + +typedef struct { + uint32_t time_milliseconds; // GPS Millisecond Time of Week + uint16_t gDOP; //Geometric DOP (scaling 0.01) + uint16_t pDOP; //Position DOP (scaling 0.01) + uint16_t tDOP; //Time DOP (scaling 0.01) + uint16_t vDOP; //Vertical DOP (scaling 0.01) + uint16_t hDOP; //Horizontal DOP (scaling 0.01) + uint16_t nDOP; //Northing DOP (scaling 0.01) + uint16_t eDOP; //Easting DOP (scaling 0.01) + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_nav_dop_packet_t; + +typedef struct { + uint32_t time_milliseconds; // GPS Millisecond Time of Week + uint8_t numCh; //Number of channels + uint8_t globalFlags; + uint16_t reserved2; + +} gps_bin_nav_svinfo_part1_packet_t; + +typedef struct { + uint8_t chn; //Channel number, 255 for SVs not assigned to a channel + uint8_t svid; //Satellite ID + uint8_t flags; + uint8_t quality; + uint8_t cno; //Carrier to Noise Ratio (Signal Strength), dbHz + int8_t elev; //Elevation in integer degrees + int16_t azim; //Azimuth in integer degrees + int32_t prRes; //Pseudo range residual in centimetres + +} gps_bin_nav_svinfo_part2_packet_t; + +typedef struct { + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_nav_svinfo_part3_packet_t; + +typedef struct { + uint32_t time_milliseconds; // GPS Millisecond Time of Week + int32_t velN; //NED north velocity, cm/s + int32_t velE; //NED east velocity, cm/s + int32_t velD; //NED down velocity, cm/s + uint32_t speed; //Speed (3-D), cm/s + uint32_t gSpeed; //Ground Speed (2-D), cm/s + int32_t heading; //Heading of motion 2-D, deg, scaling: 1e-5 + uint32_t sAcc; //Speed Accuracy Estimate, cm/s + uint32_t cAcc; //Course / Heading Accuracy Estimate, scaling: 1e-5 + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_nav_velned_packet_t; + +//typedef struct { +// int32_t time_milliseconds; // Measurement integer millisecond GPS time of week +// int16_t week; //Measurement GPS week number +// uint8_t numVis; //Number of visible satellites +// +// //... rest of package is not used in this implementation +// +//} gps_bin_rxm_svsi_packet_t; + +typedef struct { + uint8_t clsID; + uint8_t msgID; + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_ack_ack_packet_t; + +typedef struct { + uint8_t clsID; + uint8_t msgID; + + uint8_t ck_a; + uint8_t ck_b; +} gps_bin_ack_nak_packet_t; + +typedef struct { + uint8_t clsID; + uint8_t msgID; + uint16_t length; + uint8_t portID; + uint8_t res0; + uint16_t res1; + uint32_t mode; + uint32_t baudRate; + uint16_t inProtoMask; + uint16_t outProtoMask; + uint16_t flags; + uint16_t pad; + uint8_t ck_a; + uint8_t ck_b; +} type_gps_bin_cfg_prt_packet_t; + +typedef struct { + uint8_t clsID; + uint8_t msgID; + uint16_t length; + uint16_t measRate; + uint16_t navRate; + uint16_t timeRef; + uint8_t ck_a; + uint8_t ck_b; +} type_gps_bin_cfg_rate_packet_t; + +typedef struct { + uint8_t clsID; + uint8_t msgID; + uint16_t length; + uint16_t mask; + uint8_t dynModel; + uint8_t fixMode; + int32_t fixedAlt; + uint32_t fixedAltVar; + int8_t minElev; + uint8_t drLimit; + uint16_t pDop; + uint16_t tDop; + uint16_t pAcc; + uint16_t tAcc; + uint8_t staticHoldThresh; + uint8_t dgpsTimeOut; + uint32_t reserved2; + uint32_t reserved3; + uint32_t reserved4; + uint8_t ck_a; + uint8_t ck_b; +} type_gps_bin_cfg_nav5_packet_t; + +typedef struct { + uint8_t clsID; + uint8_t msgID; + uint16_t length; + uint8_t msgClass_payload; + uint8_t msgID_payload; + uint8_t rate[6]; + uint8_t ck_a; + uint8_t ck_b; +} type_gps_bin_cfg_msg_packet_t; + + +// END the structures of the binary packets +// ************ + +typedef enum { + UBX_CONFIG_STATE_PRT = 0, + UBX_CONFIG_STATE_PRT_NEW_BAUDRATE, + UBX_CONFIG_STATE_RATE, + UBX_CONFIG_STATE_NAV5, + UBX_CONFIG_STATE_MSG_NAV_POSLLH, + UBX_CONFIG_STATE_MSG_NAV_TIMEUTC, + UBX_CONFIG_STATE_MSG_NAV_DOP, + UBX_CONFIG_STATE_MSG_NAV_SVINFO, + UBX_CONFIG_STATE_MSG_NAV_SOL, + UBX_CONFIG_STATE_MSG_NAV_VELNED, +// UBX_CONFIG_STATE_MSG_RXM_SVSI, + UBX_CONFIG_STATE_CONFIGURED +} ubx_config_state_t; + +typedef enum { + CLASS_UNKNOWN = 0, + NAV = 1, + RXM = 2, + ACK = 3, + CFG = 4 +} ubx_message_class_t; + +typedef enum { + //these numbers do NOT correspond to the message id numbers of the ubx protocol + ID_UNKNOWN = 0, + NAV_POSLLH, + NAV_SOL, + NAV_TIMEUTC, + NAV_DOP, + NAV_SVINFO, + NAV_VELNED, +// RXM_SVSI, + CFG_NAV5, + ACK_ACK, + ACK_NAK, +} ubx_message_id_t; + +typedef enum { + UBX_DECODE_UNINIT = 0, + UBX_DECODE_GOT_SYNC1, + UBX_DECODE_GOT_SYNC2, + UBX_DECODE_GOT_CLASS, + UBX_DECODE_GOT_MESSAGEID, + UBX_DECODE_GOT_LENGTH1, + UBX_DECODE_GOT_LENGTH2 +} ubx_decode_state_t; + +//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t; +#pragma pack(pop) + +#define RECV_BUFFER_SIZE 500 //The NAV-SOL messages really need such a big buffer + +class UBX : public GPS_Helper +{ +public: + UBX(); + ~UBX(); + + void configure(bool&, bool&, unsigned&, uint8_t*, int&, const unsigned); + int parse(uint8_t, struct vehicle_gps_position_s*); + +private: + void decodeInit(void); + void addByteToChecksum(uint8_t); + void addChecksumToMessage(uint8_t*, const unsigned); + unsigned _waited; + bool _waiting_for_ack; + ubx_config_state_t _config_state; + ubx_decode_state_t _decode_state; + uint8_t _rx_buffer[RECV_BUFFER_SIZE]; + unsigned _rx_count; + uint8_t _rx_ck_a; + uint8_t _rx_ck_b; + ubx_message_class_t _message_class; + ubx_message_id_t _message_id; + unsigned _payload_size; + bool _new_nav_posllh; + bool _new_nav_timeutc; + bool _new_nav_dop; + bool _new_nav_sol; + bool _new_nav_velned; +}; + +#endif /* UBX_H_ */ From 3fd8c73bfbdad1fdb9b5b31337cf6eb3fa46c34c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 4 Feb 2013 15:58:53 +0100 Subject: [PATCH 02/20] Disabled old-style gps interface, enabled GPS driver --- apps/drivers/gps/gps.cpp | 2 ++ nuttx/configs/px4fmu/nsh/appconfig | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 7d6f7144ef..9fd679240f 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -471,6 +471,8 @@ GPS::set_baudrate(unsigned baud) warnx("ERROR setting baudrate (tcsetattr)\n"); return -1; } + + /* XXX if resetting the parser here, ensure it does exist (check for null pointer) */ } void diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 653f97de11..710e2fb5f5 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -80,7 +80,6 @@ CONFIGURED_APPS += uORB CONFIGURED_APPS += mavlink CONFIGURED_APPS += mavlink_onboard -CONFIGURED_APPS += gps CONFIGURED_APPS += commander CONFIGURED_APPS += sdlog CONFIGURED_APPS += sensors @@ -114,6 +113,7 @@ CONFIGURED_APPS += drivers/stm32/tone_alarm CONFIGURED_APPS += drivers/stm32/adc CONFIGURED_APPS += drivers/px4fmu CONFIGURED_APPS += drivers/hil +CONFIGURED_APPS += drivers/gps # Testing stuff CONFIGURED_APPS += px4/sensors_bringup From 12f4cb2dc38303b58750a8f3b120738a291ac8d1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 4 Feb 2013 16:13:17 +0100 Subject: [PATCH 03/20] Tuned GPS update rates --- apps/mavlink/mavlink.c | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index ceb7c25549..09abcf2693 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -625,7 +625,9 @@ int mavlink_thread_main(int argc, char *argv[]) /* 20 Hz / 50 ms */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 10); set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 50); - /* 2 Hz */ + /* 10 Hz */ + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW, 100); + /* 10 Hz */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 100); } else if (baudrate >= 115200) { @@ -634,8 +636,10 @@ int mavlink_thread_main(int argc, char *argv[]) set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_RAW_IMU, 50); set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 50); set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 50); - /* 5 Hz / 100 ms */ + /* 5 Hz / 200 ms */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 200); + /* 5 Hz / 200 ms */ + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW, 200); /* 2 Hz */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500); @@ -651,6 +655,8 @@ int mavlink_thread_main(int argc, char *argv[]) set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 500); /* 2 Hz */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500); + /* 2 Hz */ + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW, 500); } else { /* very low baud rate, limit to 1 Hz / 1000 ms */ From 30f028908a69db058c05b9af7e31c8c52c3bc339 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 4 Feb 2013 16:15:48 +0100 Subject: [PATCH 04/20] Fixed typo --- apps/mavlink/mavlink.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index 09abcf2693..b958d5f96c 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -626,7 +626,7 @@ int mavlink_thread_main(int argc, char *argv[]) set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 10); set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 50); /* 10 Hz */ - set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW, 100); + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW_INT, 100); /* 10 Hz */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 100); @@ -639,7 +639,7 @@ int mavlink_thread_main(int argc, char *argv[]) /* 5 Hz / 200 ms */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 200); /* 5 Hz / 200 ms */ - set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW, 200); + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW_INT, 200); /* 2 Hz */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500); @@ -656,7 +656,7 @@ int mavlink_thread_main(int argc, char *argv[]) /* 2 Hz */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500); /* 2 Hz */ - set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW, 500); + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW_INT, 500); } else { /* very low baud rate, limit to 1 Hz / 1000 ms */ From 13ec0675703ecc9c7bccb22ef3cd049888dd1abb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 4 Feb 2013 17:55:58 +0100 Subject: [PATCH 05/20] Minor quick cleanups --- apps/drivers/gps/gps.cpp | 108 +++++++++++++++++++++++++++------------ apps/drivers/gps/ubx.cpp | 28 +++++----- 2 files changed, 89 insertions(+), 47 deletions(-) diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 9fd679240f..6f7310cc5c 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -107,30 +107,29 @@ public: private: - int _task_should_exit; - int _serial_fd; ///< serial interface to GPS + int _task_should_exit; + int _serial_fd; ///< serial interface to GPS unsigned _baudrate; unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; uint8_t _send_buffer[SEND_BUFFER_LENGTH]; - perf_counter_t _sample_perf; - perf_counter_t _comms_errors; - perf_counter_t _buffer_overflows; - volatile int _task; ///< worker task + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; + perf_counter_t _buffer_overflows; + volatile int _task; ///< worker task bool _response_received; bool _config_needed; bool _baudrate_changed; bool _mode_changed; bool _healthy; - gps_driver_mode_t _mode; + gps_driver_mode_t _mode; unsigned _messages_received; + float _rate; ///< position update rate - GPS_Helper *_Helper; ///< Class for either UBX, MTK or NMEA helper + GPS_Helper *_Helper; ///< class for either UBX, MTK or NMEA helper - struct vehicle_gps_position_s _report; - orb_advert_t _report_pub; - - orb_advert_t _gps_topic; + struct vehicle_gps_position_s _report; ///< the current GPS report + orb_advert_t _report_pub; ///< the publication topic, only valid on first valid GPS module message void recv(); @@ -140,16 +139,19 @@ private: /** - * worker task + * Worker task. */ - void task_main(void); + void task_main(void); - int set_baudrate(unsigned baud); + /** + * Set the module baud rate + */ + int set_baudrate(unsigned baud); /** * Send a reset command to the GPS */ - void cmd_reset(); + void cmd_reset(); }; @@ -177,13 +179,15 @@ GPS::GPS() : _healthy(false), _mode(GPS_DRIVER_MODE_UBX), _messages_received(0), - _Helper(nullptr) + _Helper(nullptr), + _rate(0.0f), + _report_pub(-1) { /* we need this potentially before it could be set in task_main */ g_dev = this; + memset(&_report, 0, sizeof(_report)); _debug_enabled = true; - debug("[gps driver] instantiated"); } GPS::~GPS() @@ -213,16 +217,13 @@ GPS::init() goto out; /* start the IO interface task */ - _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 4096, (main_t)&GPS::task_main_trampoline, nullptr); + _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr); if (_task < 0) { - debug("task start failed: %d", errno); + warnx("task start failed: %d", errno); return -errno; } -// if (_gps_topic < 0) -// debug("failed to create GPS object"); - ret = OK; out: return ret; @@ -231,6 +232,8 @@ out: int GPS::ioctl(struct file *filp, int cmd, unsigned long arg) { + lock(); + int ret = OK; switch (cmd) { @@ -263,6 +266,8 @@ GPS::ioctl(struct file *filp, int cmd, unsigned long arg) break; } + unlock(); + return ret; } @@ -298,10 +303,6 @@ GPS::task_main() { log("starting"); - _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); - - memset(&_report, 0, sizeof(_report)); - /* open the serial port */ _serial_fd = ::open("/dev/ttyS3", O_RDWR); @@ -311,7 +312,9 @@ GPS::task_main() if (_serial_fd < 0) { log("failed to open serial port: %d", errno); - goto out; + /* tell the dtor that we are exiting, set error code */ + _task = -1; + _exit(1); } /* poll descriptor */ @@ -329,6 +332,9 @@ GPS::task_main() time_before_configuration = hrt_absolute_time(); + uint64_t last_rate_measurement = hrt_absolute_time(); + unsigned last_rate_count = 0; + /* loop handling received serial bytes */ while (!_task_should_exit) { @@ -369,9 +375,9 @@ GPS::task_main() if (_config_needed) { poll_timeout = 50; } else { - poll_timeout = 250; + poll_timeout = 400; } - /* sleep waiting for data, but no more than 1000ms */ + /* sleep waiting for data, but no more than the poll timeout */ unlock(); int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), poll_timeout); lock(); @@ -386,7 +392,7 @@ GPS::task_main() config(); if (_config_needed == false) { _config_needed = true; - debug("Lost GPS module"); + warnx("lost GPS module"); } } else if (ret > 0) { /* if we have new data from GPS, go handle it */ @@ -411,8 +417,22 @@ GPS::task_main() debug("Found GPS module"); } - orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + /* opportunistic publishing - else invalid data would end up on the bus */ + if (_report_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + } else { + _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } + _messages_received = 0; + last_rate_count++; + + /* measure update rate every 5 seconds */ + if (hrt_absolute_time() - last_rate_measurement > 5000000) { + _rate = last_rate_count / (float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f; + last_rate_measurement = hrt_absolute_time(); + last_rate_count = 0; + } } } } @@ -484,7 +504,29 @@ GPS::cmd_reset() void GPS::print_info() { - + switch (_mode) { + case GPS_DRIVER_MODE_UBX: + warnx("protocol: UBX"); + break; + case GPS_DRIVER_MODE_MTK19: + warnx("protocol: MTK 1.9"); + break; + case GPS_DRIVER_MODE_MTK16: + warnx("protocol: MTK 1.6"); + break; + case GPS_DRIVER_MODE_NMEA: + warnx("protocol: NMEA"); + break; + default: + break; + } + warnx("baudrate: %d, status: %s", _baudrate, (_config_needed) ? "NOT OK" : "OK"); + if (_report.timestamp != 0) { + warnx("position lock: %dD, last update %d seconds ago", (int)_report.fix_type, + int((hrt_absolute_time() - _report.timestamp) / 1000000)); + warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt); + warnx("update rate: %6.2f Hz", (double)_rate); + } } /** diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index 981b023e55..7e95514ddc 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -371,7 +371,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) } break; default: //should not happen because we set the class - printf("UBX Error, we set a class that we don't know\n"); + warnx("UBX Error, we set a class that we don't know\n"); decodeInit(); break; } @@ -410,7 +410,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_posllh = true; } else { - printf("[gps] NAV_POSLLH: checksum invalid\n"); + warnx("NAV_POSLLH: checksum invalid\n"); } // Reset state machine to decode next packet @@ -437,7 +437,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_sol = true; } else { - printf("[gps] NAV_SOL: checksum invalid\n"); + warnx("NAV_SOL: checksum invalid\n"); } // Reset state machine to decode next packet @@ -463,7 +463,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_dop = true; } else { - printf("[gps] NAV_DOP: checksum invalid\n"); + warnx("NAV_DOP: checksum invalid\n"); } // Reset state machine to decode next packet @@ -624,7 +624,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_velned = true; } else { - printf("[gps] NAV_VELNED: checksum invalid\n"); + warnx("NAV_VELNED: checksum invalid\n"); } // Reset state machine to decode next packet @@ -651,7 +651,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // ret = 1; // // } else { -// printf("[gps] RXM_SVSI: checksum invalid\n"); +// warnx("RXM_SVSI: checksum invalid\n"); // } // // // Reset state machine to decode next packet @@ -719,7 +719,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) break; } } else { - printf("[gps] ACK_ACK: checksum invalid\n"); + warnx("ACK_ACK: checksum invalid\n"); } // Reset state machine to decode next packet @@ -736,11 +736,11 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) //Check if checksum is valid if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - printf("[gps] the ubx gps returned: not acknowledged\n"); + warnx("the ubx gps returned: not acknowledged\n"); ret = 1; } else { - printf("[gps] ACK_NAK: checksum invalid\n"); + warnx("ACK_NAK: checksum invalid\n"); } // Reset state machine to decode next packet @@ -768,16 +768,16 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) break; } - /* return 1 when all needed messages have arrived */ + /* return 1 when position updates and the remaining packets updated at least once */ if(_new_nav_posllh &&_new_nav_timeutc && _new_nav_dop && _new_nav_sol && _new_nav_velned) { gps_position->timestamp = hrt_absolute_time(); ret = 1; _new_nav_posllh = false; - _new_nav_timeutc = false; - _new_nav_dop = false; - _new_nav_sol = false; - _new_nav_velned = false; + // _new_nav_timeutc = false; + // _new_nav_dop = false; + // _new_nav_sol = false; + // _new_nav_velned = false; } return ret; From d4bd7225baa8c46e6a93dcd063f66ce53fe88e69 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 4 Feb 2013 18:00:10 +0100 Subject: [PATCH 06/20] More cleanup --- apps/drivers/gps/gps.cpp | 3 ++- apps/drivers/gps/ubx.cpp | 22 +++++++++++----------- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 6f7310cc5c..bd77e8969a 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -341,7 +341,8 @@ GPS::task_main() if (_mode_changed) { if (_Helper != nullptr) { delete(_Helper); - _Helper = nullptr; // XXX is this needed? + /* set to zero to ensure parser is not used while not instantiated */ + _Helper = nullptr; } switch (_mode) { diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index 7e95514ddc..fe4758d8cf 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -371,7 +371,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) } break; default: //should not happen because we set the class - warnx("UBX Error, we set a class that we don't know\n"); + warnx("UBX Error, we set a class that we don't know"); decodeInit(); break; } @@ -410,7 +410,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_posllh = true; } else { - warnx("NAV_POSLLH: checksum invalid\n"); + warnx("NAV_POSLLH: checksum invalid"); } // Reset state machine to decode next packet @@ -437,7 +437,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_sol = true; } else { - warnx("NAV_SOL: checksum invalid\n"); + warnx("NAV_SOL: checksum invalid"); } // Reset state machine to decode next packet @@ -463,7 +463,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_dop = true; } else { - warnx("NAV_DOP: checksum invalid\n"); + warnx("NAV_DOP: checksum invalid"); } // Reset state machine to decode next packet @@ -499,7 +499,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_timeutc = true; } else { - printf("\t[gps] NAV_TIMEUTC: checksum invalid\n"); + warnx("NAV_TIMEUTC: checksum invalid"); } // Reset state machine to decode next packet @@ -593,7 +593,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // as this message arrives only with 1Hz and is not essential, we don't take it into account for the report } else { - printf("\t[gps] NAV_SVINFO: checksum invalid\n"); + warnx("NAV_SVINFO: checksum invalid"); } // Reset state machine to decode next packet @@ -624,7 +624,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) _new_nav_velned = true; } else { - warnx("NAV_VELNED: checksum invalid\n"); + warnx("NAV_VELNED: checksum invalid"); } // Reset state machine to decode next packet @@ -719,7 +719,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) break; } } else { - warnx("ACK_ACK: checksum invalid\n"); + warnx("ACK_ACK: checksum invalid"); } // Reset state machine to decode next packet @@ -736,7 +736,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) //Check if checksum is valid if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - warnx("the ubx gps returned: not acknowledged\n"); + warnx("UBX: NO ACK"); ret = 1; } else { @@ -751,7 +751,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) } default: //we don't know the message - printf("Unknown message received: %d-%d\n",_message_class,_message_id); + warnx("UBX: Unknown message received: %d-%d\n",_message_class,_message_id); decodeInit(); break; @@ -760,7 +760,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) if (_rx_count < RECV_BUFFER_SIZE) { _rx_count++; } else { - printf("Buffer full"); + warnx("buffer overflow"); decodeInit(); } break; From cb0fd834ae15c45cf6993f8c9eea9c99b2b153dd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 4 Feb 2013 18:14:55 +0100 Subject: [PATCH 07/20] Minor polishing, fixed rate and last measurement indication --- apps/drivers/gps/gps.cpp | 6 +++--- apps/drivers/gps/ubx.cpp | 6 ------ apps/mavlink/orb_listener.c | 2 +- 3 files changed, 4 insertions(+), 10 deletions(-) diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index bd77e8969a..49b94fc2e7 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -430,7 +430,7 @@ GPS::task_main() /* measure update rate every 5 seconds */ if (hrt_absolute_time() - last_rate_measurement > 5000000) { - _rate = last_rate_count / (float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f; + _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f); last_rate_measurement = hrt_absolute_time(); last_rate_count = 0; } @@ -523,8 +523,8 @@ GPS::print_info() } warnx("baudrate: %d, status: %s", _baudrate, (_config_needed) ? "NOT OK" : "OK"); if (_report.timestamp != 0) { - warnx("position lock: %dD, last update %d seconds ago", (int)_report.fix_type, - int((hrt_absolute_time() - _report.timestamp) / 1000000)); + warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type, + ((float)(hrt_absolute_time() - _report.timestamp) / 1000000.0f)); warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt); warnx("update rate: %6.2f Hz", (double)_rate); } diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index fe4758d8cf..1105e0da40 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -429,7 +429,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) gps_position->fix_type = packet->gpsFix; - gps_position->timestamp = hrt_absolute_time(); gps_position->counter++; gps_position->s_variance = packet->sAcc; gps_position->p_variance = packet->pAcc; @@ -457,7 +456,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) gps_position->eph = packet->hDOP; gps_position->epv = packet->vDOP; - gps_position->timestamp = hrt_absolute_time(); gps_position->counter++; _new_nav_dop = true; @@ -493,7 +491,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); - gps_position->timestamp = hrt_absolute_time(); gps_position->counter++; _new_nav_timeutc = true; @@ -587,7 +584,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) } gps_position->satellites_visible = satellites_used++; // visible ~= used but we are interested in the used ones - gps_position->timestamp = hrt_absolute_time(); gps_position->counter++; // as this message arrives only with 1Hz and is not essential, we don't take it into account for the report @@ -617,7 +613,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) gps_position->vel_ned_valid = true; gps_position->cog = (uint16_t)((float)(packet->heading) * 1e-3f); - gps_position->timestamp = hrt_absolute_time(); gps_position->counter++; @@ -645,7 +640,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) { // // gps_position->satellites_visible = packet->numVis; -// gps_position->timestamp = hrt_absolute_time(); // gps_position->counter++; // _last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time(); // ret = 1; diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index ec5149745c..18da70f610 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -698,7 +698,7 @@ uorb_receive_start(void) /* --- GPS VALUE --- */ mavlink_subs.gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); - orb_set_interval(mavlink_subs.gps_sub, 1000); /* 1Hz updates */ + orb_set_interval(mavlink_subs.gps_sub, 200); /* 5Hz updates */ /* --- HOME POSITION --- */ mavlink_subs.home_sub = orb_subscribe(ORB_ID(home_position)); From 039d394c207830a2c9c3a22e03302c867bd57af6 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 4 Feb 2013 16:27:01 -0800 Subject: [PATCH 08/20] Merged with newer, cleaned up code, fixed the checksum error --- apps/drivers/drv_gps.h | 2 - apps/drivers/gps/gps.cpp | 130 +++++++++++++++++++--------------- apps/drivers/gps/gps_helper.h | 5 +- apps/drivers/gps/ubx.cpp | 107 ++++++++++++++-------------- apps/drivers/gps/ubx.h | 114 +++++++++++++++-------------- 5 files changed, 191 insertions(+), 167 deletions(-) diff --git a/apps/drivers/drv_gps.h b/apps/drivers/drv_gps.h index 89fc54b0d9..1ae27ed2f9 100644 --- a/apps/drivers/drv_gps.h +++ b/apps/drivers/drv_gps.h @@ -54,8 +54,6 @@ typedef enum { } gps_driver_mode_t; - - /* * ObjDev tag for GPS data. */ diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 49b94fc2e7..450b3091bd 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -33,7 +33,7 @@ /** * @file gps.cpp - * Driver for the GPS on UART6 + * Driver for the GPS on a serial port */ #include @@ -107,46 +107,41 @@ public: private: - int _task_should_exit; - int _serial_fd; ///< serial interface to GPS - unsigned _baudrate; - unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; - uint8_t _send_buffer[SEND_BUFFER_LENGTH]; - perf_counter_t _sample_perf; - perf_counter_t _comms_errors; - perf_counter_t _buffer_overflows; - volatile int _task; ///< worker task + bool _task_should_exit; ///< flag to make the main worker task exit + int _serial_fd; ///< serial interface to GPS + unsigned _baudrate; ///< current baudrate + unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; ///< try different baudrates that GPS could be set to + volatile int _task; ///< worker task + bool _config_needed; ///< flag to signal that configuration of GPS is needed + bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed + bool _mode_changed; ///< flag that the GPS mode has changed + gps_driver_mode_t _mode; ///< current mode + GPS_Helper *_Helper; ///< Class for either UBX, MTK or NMEA helper + struct vehicle_gps_position_s _report; ///< uORB topic for gps position + orb_advert_t _report_pub; ///< uORB pub for gps position + float _rate; ///< position update rate - bool _response_received; - bool _config_needed; - bool _baudrate_changed; - bool _mode_changed; - bool _healthy; - gps_driver_mode_t _mode; - unsigned _messages_received; - float _rate; ///< position update rate - - GPS_Helper *_Helper; ///< class for either UBX, MTK or NMEA helper - - struct vehicle_gps_position_s _report; ///< the current GPS report - orb_advert_t _report_pub; ///< the publication topic, only valid on first valid GPS module message - - void recv(); + /** + * Try to configure the GPS, handle outgoing communication to the GPS + */ void config(); + /** + * Trampoline to the worker task + */ static void task_main_trampoline(void *arg); /** - * Worker task. + * Worker task: main GPS thread that configures the GPS and parses incoming data, always running */ void task_main(void); /** - * Set the module baud rate + * Set the baudrate of the UART to the GPS */ - int set_baudrate(unsigned baud); + int set_baudrate(unsigned baud); /** * Send a reset command to the GPS @@ -176,12 +171,10 @@ GPS::GPS() : _config_needed(true), _baudrate_changed(false), _mode_changed(true), - _healthy(false), _mode(GPS_DRIVER_MODE_UBX), - _messages_received(0), _Helper(nullptr), - _rate(0.0f), - _report_pub(-1) + _report_pub(-1), + _rate(0.0f) { /* we need this potentially before it could be set in task_main */ g_dev = this; @@ -216,7 +209,7 @@ GPS::init() if (CDev::init() != OK) goto out; - /* start the IO interface task */ + /* start the GPS driver worker task */ _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr); if (_task < 0) { @@ -275,17 +268,22 @@ void GPS::config() { int length = 0; + uint8_t send_buffer[SEND_BUFFER_LENGTH]; - _Helper->configure(_config_needed, _baudrate_changed, _baudrate, _send_buffer, length, SEND_BUFFER_LENGTH); + _Helper->configure(_config_needed, _baudrate_changed, _baudrate, send_buffer, length, SEND_BUFFER_LENGTH); - /* the message needs to be sent at the old baudrate */ + /* The config message is sent sent at the old baudrate */ if (length > 0) { - if (length != ::write(_serial_fd, _send_buffer, length)) { + + if (length != ::write(_serial_fd, send_buffer, length)) { debug("write config failed"); return; } } + /* Sometimes the baudrate needs to be changed, for instance UBX with factory settings are changed + * from 9600 to 38400 + */ if (_baudrate_changed) { set_baudrate(_baudrate); _baudrate_changed = false; @@ -304,11 +302,10 @@ GPS::task_main() log("starting"); /* open the serial port */ - _serial_fd = ::open("/dev/ttyS3", O_RDWR); + _serial_fd = ::open("/dev/ttyS3", O_RDWR); //TODO make the device dynamic depending on startup parameters - uint8_t buf[256]; - int baud_i = 0; - uint64_t time_before_configuration; + /* buffer to read from the serial port */ + uint8_t buf[32]; if (_serial_fd < 0) { log("failed to open serial port: %d", errno); @@ -326,16 +323,16 @@ GPS::task_main() /* lock against the ioctl handler */ lock(); - + unsigned baud_i = 0; _baudrate = _baudrates_to_try[baud_i]; set_baudrate(_baudrate); - time_before_configuration = hrt_absolute_time(); + uint64_t time_before_configuration = hrt_absolute_time(); uint64_t last_rate_measurement = hrt_absolute_time(); unsigned last_rate_count = 0; - /* loop handling received serial bytes */ + /* loop handling received serial bytes and also configuring in between */ while (!_task_should_exit) { if (_mode_changed) { @@ -364,14 +361,17 @@ GPS::task_main() _mode_changed = false; } + /* If a configuration does not finish in the config timeout, change the baudrate */ if (_config_needed && time_before_configuration + CONFIG_TIMEOUT < hrt_absolute_time()) { baud_i = (baud_i+1)%NUMBER_OF_BAUDRATES; _baudrate = _baudrates_to_try[baud_i]; set_baudrate(_baudrate); + _Helper->reset(); time_before_configuration = hrt_absolute_time(); } - + /* during configuration, the timeout should be small, so that we can send config messages in between parsing, + * but during normal operation, it should never timeout because updates should arrive with 5Hz */ int poll_timeout; if (_config_needed) { poll_timeout = 50; @@ -409,11 +409,21 @@ GPS::task_main() /* pass received bytes to the packet decoder */ int j; + int ret_parse = 0; for (j = 0; j < count; j++) { - _messages_received += _Helper->parse(buf[j], &_report); + ret_parse += _Helper->parse(buf[j], &_report); } - if (_messages_received > 0) { - if (_config_needed == true) { + + if (ret_parse < 0) { + /* This means something went wrong in the parser, let's reconfigure */ + if (!_config_needed) { + _config_needed = true; + debug("Lost GPS module"); + } + config(); + } else if (ret_parse > 0) { + /* Looks like we got a valid position update, stop configuring and publish it */ + if (_config_needed) { _config_needed = false; debug("Found GPS module"); } @@ -424,8 +434,6 @@ GPS::task_main() } else { _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); } - - _messages_received = 0; last_rate_count++; /* measure update rate every 5 seconds */ @@ -435,10 +443,10 @@ GPS::task_main() last_rate_count = 0; } } + /* else if ret_parse == 0: just keep parsing */ } } } -out: debug("exiting"); ::close(_serial_fd); @@ -469,7 +477,6 @@ GPS::set_baudrate(unsigned baud) warnx("ERROR: Unsupported baudrate: %d\n", baud); return -EINVAL; } - struct termios uart_config; int termios_state; @@ -482,24 +489,26 @@ GPS::set_baudrate(unsigned baud) uart_config.c_cflag &= ~(CSTOPB | PARENB); /* set baud rate */ - if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - warnx("ERROR setting config: %d (cfsetispeed, cfsetospeed)\n", termios_state); + if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { + warnx("ERROR setting config: %d (cfsetispeed)\n", termios_state); + return -1; + } + if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { + warnx("ERROR setting config: %d (cfsetospeed)\n", termios_state); return -1; } - - if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) { warnx("ERROR setting baudrate (tcsetattr)\n"); return -1; } - /* XXX if resetting the parser here, ensure it does exist (check for null pointer) */ + return 0; } void GPS::cmd_reset() { - _healthy = false; + _config_needed = true; } void @@ -524,10 +533,12 @@ GPS::print_info() warnx("baudrate: %d, status: %s", _baudrate, (_config_needed) ? "NOT OK" : "OK"); if (_report.timestamp != 0) { warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type, - ((float)(hrt_absolute_time() - _report.timestamp) / 1000000.0f)); + (double)((float)(hrt_absolute_time() - _report.timestamp) / 1000000.0f)); warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt); warnx("update rate: %6.2f Hz", (double)_rate); } + + usleep(100000); } /** @@ -583,6 +594,9 @@ fail: errx(1, "driver start failed"); } +/** + * Stop the driver. + */ void stop() { diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h index baacf7cb47..8a6b0148b7 100644 --- a/apps/drivers/gps/gps_helper.h +++ b/apps/drivers/gps/gps_helper.h @@ -40,8 +40,9 @@ class GPS_Helper { public: - virtual void configure(bool&, bool&, unsigned&, uint8_t*, int&, const unsigned) = 0; - virtual int parse(uint8_t, struct vehicle_gps_position_s*) = 0; + virtual void reset() = 0; + virtual void configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, uint8_t *buffer, int &length, const unsigned max_length) = 0; + virtual int parse(uint8_t b, struct vehicle_gps_position_s *gps_position) = 0; }; #endif /* GPS_HELPER_H */ diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index 1105e0da40..66a891da4f 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -48,36 +48,41 @@ UBX::UBX() : -_waited(0), _config_state(UBX_CONFIG_STATE_PRT), +_waiting_for_ack(false), _new_nav_posllh(false), _new_nav_timeutc(false), _new_nav_dop(false), _new_nav_sol(false), _new_nav_velned(false) { - decodeInit(); - _waiting_for_ack = false; + reset(); } UBX::~UBX() { } +void +UBX::reset() +{ + decodeInit(); + _config_state = UBX_CONFIG_STATE_PRT; + _waiting_for_ack = false; +} + void UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, uint8_t *buffer, int &length, const unsigned max_length) { - /* make sure the buffer to write the message is long enough */ + /* make sure the buffer, where the message is written to, is long enough */ assert(sizeof(type_gps_bin_cfg_prt_packet_t)+2 <= max_length); - /* try again after 10 times */ - if (_waited > 10) { - _waiting_for_ack = false; - } - + /* Only send a new config message when we got the ACK of the last one, + * otherwise we might not configure all the messages because the ACK comes from an older/previos CFD command + * reason being that the ACK only includes CFG-MSG but not to which NAV MSG it belongs. + */ if (!_waiting_for_ack) { _waiting_for_ack = true; - _waited = 0; if (_config_state == UBX_CONFIG_STATE_CONFIGURED) { config_needed = false; length = 0; @@ -85,10 +90,15 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, _waiting_for_ack = false; return; } else if (_config_state == UBX_CONFIG_STATE_PRT) { - /* send a CFT-PRT message to define set ubx protocol and leave the baudrate as is, we just want an ACK-ACK from this */ + + /* Send a CFG-PRT message to set the UBX protocol for in and out + * and leave the baudrate as it is, we just want an ACK-ACK from this + */ type_gps_bin_cfg_prt_packet_t cfg_prt_packet; + /* Set everything else of the packet to 0, otherwise the module wont accept it */ memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); + /* Define the package contents, don't change the baudrate */ cfg_prt_packet.clsID = UBX_CLASS_CFG; cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; @@ -98,18 +108,20 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; + /* Calculate the checksum now */ addChecksumToMessage((uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); + /* Start with the two sync bytes */ buffer[0] = UBX_SYNC1; buffer[1] = UBX_SYNC2; + /* Copy it to the buffer that will be written back in the main gps driver */ memcpy(&(buffer[2]), &cfg_prt_packet, sizeof(cfg_prt_packet)); + /* Set the length of the packet (plus the 2 sync bytes) */ length = sizeof(cfg_prt_packet)+2; } else if (_config_state == UBX_CONFIG_STATE_PRT_NEW_BAUDRATE) { -// printf("Send change of baudrate now\n"); - - /* send a CFT-PRT message to define set ubx protocol and and baudrate, now let's try to switch the baudrate */ + /* Send a CFG-PRT message again, this time change the baudrate */ type_gps_bin_cfg_prt_packet_t cfg_prt_packet; memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); @@ -129,18 +141,15 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, memcpy(&(buffer[2]), &cfg_prt_packet, sizeof(cfg_prt_packet)); length = sizeof(cfg_prt_packet)+2; - /* detection when the baudrate has been changed in the first step */ + /* If the new baudrate will be different from the current one, we should report that back to the driver */ if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) { - /* set a flag and exit */ baudrate=UBX_CFG_PRT_PAYLOAD_BAUDRATE; baudrate_changed = true; - _config_state = UBX_CONFIG_STATE_RATE; - _waiting_for_ack = false; - return; + /* Don't wait for an ACK, we're switching baudrate and we might never get, + * after that, start fresh */ + reset(); } - - } else if (_config_state == UBX_CONFIG_STATE_RATE) { /* send a CFT-RATE message to define update rate */ @@ -162,9 +171,9 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, length = sizeof(cfg_rate_packet)+2; } else if (_config_state == UBX_CONFIG_STATE_NAV5) { - /* send a NAV5 message to set the options for the internal estimator */ + /* send a NAV5 message to set the options for the internal filter */ type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet; - memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet)); //set everything to 0 + memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet)); cfg_nav5_packet.clsID = UBX_CLASS_CFG; cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5; @@ -181,15 +190,16 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, length = sizeof(cfg_nav5_packet)+2; } else { - /* catch the remaining config states here */ + /* Catch the remaining config states here, they all need the same packet type */ type_gps_bin_cfg_msg_packet_t cfg_msg_packet; - memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet)); //set everything to 0 + memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet)); cfg_msg_packet.clsID = UBX_CLASS_CFG; cfg_msg_packet.msgID = UBX_MESSAGE_CFG_MSG; cfg_msg_packet.length = UBX_CFG_MSG_LENGTH; - cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1; + /* Choose fast 5Hz rate for all messages except SVINFO which is big and not important */ + cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_5HZ; switch (_config_state) { case UBX_CONFIG_STATE_MSG_NAV_POSLLH: @@ -207,7 +217,8 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, case UBX_CONFIG_STATE_MSG_NAV_SVINFO: cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO; - cfg_msg_packet.rate[1] = 5; + /* For satelites info 1Hz is enough */ + cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_1HZ; break; case UBX_CONFIG_STATE_MSG_NAV_SOL: cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; @@ -232,16 +243,14 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, memcpy(&(buffer[2]), &cfg_msg_packet, sizeof(cfg_msg_packet)); length = sizeof(cfg_msg_packet)+2; } - } else { - _waited++; } } int -UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) +UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) { + /* if no error happens and no new report is ready yet, ret will stay 0 */ int ret = 0; - //printf("Received char: %c\n", b); switch (_decode_state) { /* First, look for sync1 */ @@ -373,6 +382,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) default: //should not happen because we set the class warnx("UBX Error, we set a class that we don't know"); decodeInit(); + ret = -1; break; } break; @@ -415,8 +425,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // Reset state machine to decode next packet decodeInit(); - return ret; - break; } @@ -441,8 +449,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // Reset state machine to decode next packet decodeInit(); - return ret; - break; } @@ -466,8 +472,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // Reset state machine to decode next packet decodeInit(); - return ret; - break; } @@ -501,8 +505,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // Reset state machine to decode next packet decodeInit(); - return ret; - break; } @@ -594,8 +596,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // Reset state machine to decode next packet decodeInit(); - return ret; - break; } @@ -615,7 +615,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) gps_position->counter++; - _new_nav_velned = true; } else { @@ -624,8 +623,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // Reset state machine to decode next packet decodeInit(); - return ret; - break; } @@ -718,7 +715,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) // Reset state machine to decode next packet decodeInit(); - return ret; break; } @@ -730,7 +726,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) //Check if checksum is valid if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - warnx("UBX: NO ACK"); + warnx("UBX: Received: Not Acknowledged"); ret = 1; } else { @@ -751,11 +747,12 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) break; } } // end if _rx_count high enough - if (_rx_count < RECV_BUFFER_SIZE) { + else if (_rx_count < RECV_BUFFER_SIZE) { _rx_count++; } else { - warnx("buffer overflow"); + warnx("buffer full, restarting"); decodeInit(); + ret = -1; } break; default: @@ -765,13 +762,16 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s* gps_position) /* return 1 when position updates and the remaining packets updated at least once */ if(_new_nav_posllh &&_new_nav_timeutc && _new_nav_dop && _new_nav_sol && _new_nav_velned) { + /* Add timestamp to finish the report */ gps_position->timestamp = hrt_absolute_time(); - ret = 1; + /* Reset the flags */ _new_nav_posllh = false; - // _new_nav_timeutc = false; - // _new_nav_dop = false; - // _new_nav_sol = false; - // _new_nav_velned = false; + _new_nav_timeutc = false; + _new_nav_dop = false; + _new_nav_sol = false; + _new_nav_velned = false; + + ret = 1; } return ret; @@ -807,6 +807,7 @@ UBX::addChecksumToMessage(uint8_t* message, const unsigned length) ck_a = ck_a + message[i]; ck_b = ck_b + ck_a; } + /* The checksum is written to the last to bytes of a message */ message[length-2] = ck_a; message[length-1] = ck_b; } diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index dff25a518f..0cac10f0a3 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -40,16 +40,17 @@ #include "gps_helper.h" -#define UBX_NO_OF_MESSAGES 7 /**< Read 7 UBX GPS messages */ #define UBX_SYNC1 0xB5 #define UBX_SYNC2 0x62 -//UBX Protocol definitions (this is the subset of the messages that are parsed) +/* ClassIDs (the ones that are used) */ #define UBX_CLASS_NAV 0x01 //#define UBX_CLASS_RXM 0x02 #define UBX_CLASS_ACK 0x05 #define UBX_CLASS_CFG 0x06 + +/* MessageIDs (the ones that are used) */ #define UBX_MESSAGE_NAV_POSLLH 0x02 #define UBX_MESSAGE_NAV_SOL 0x06 #define UBX_MESSAGE_NAV_TIMEUTC 0x21 @@ -65,11 +66,11 @@ #define UBX_MESSAGE_CFG_RATE 0x08 #define UBX_CFG_PRT_LENGTH 20 -#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< port 1 */ +#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */ #define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ #define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */ -#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< ubx in */ -#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< ubx out */ +#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */ +#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */ #define UBX_CFG_RATE_LENGTH 6 #define UBX_CFG_RATE_PAYLOAD_MEASRATE 200 /**< 200ms for 5Hz */ @@ -83,30 +84,30 @@ #define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */ #define UBX_CFG_MSG_LENGTH 8 -#define UBX_CFG_MSG_PAYLOAD_RATE1 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} UART1 chosen */ - +#define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ +#define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ // ************ /** the structures of the binary packets */ #pragma pack(push, 1) typedef struct { - uint32_t time_milliseconds; // GPS Millisecond Time of Week - int32_t lon; // Longitude * 1e-7, deg - int32_t lat; // Latitude * 1e-7, deg - int32_t height; // Height above Ellipsoid, mm - int32_t height_msl; // Height above mean sea level, mm - uint32_t hAcc; // Horizontal Accuracy Estimate, mm - uint32_t vAcc; // Vertical Accuracy Estimate, mm + uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ + int32_t lon; /**< Longitude * 1e-7, deg */ + int32_t lat; /**< Latitude * 1e-7, deg */ + int32_t height; /**< Height above Ellipsoid, mm */ + int32_t height_msl; /**< Height above mean sea level, mm */ + uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */ + uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */ uint8_t ck_a; uint8_t ck_b; } gps_bin_nav_posllh_packet_t; typedef struct { - uint32_t time_milliseconds; // GPS Millisecond Time of Week - int32_t time_nanoseconds; // Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 - int16_t week; // GPS week (GPS time) - uint8_t gpsFix; //GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix + uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ + int32_t time_nanoseconds; /**< Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 */ + int16_t week; /**< GPS week (GPS time) */ + uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */ uint8_t flags; int32_t ecefX; int32_t ecefY; @@ -125,50 +126,50 @@ typedef struct { } gps_bin_nav_sol_packet_t; typedef struct { - uint32_t time_milliseconds; // GPS Millisecond Time of Week - uint32_t time_accuracy; //Time Accuracy Estimate, ns - int32_t time_nanoseconds; //Nanoseconds of second, range -1e9 .. 1e9 (UTC) - uint16_t year; //Year, range 1999..2099 (UTC) - uint8_t month; //Month, range 1..12 (UTC) - uint8_t day; //Day of Month, range 1..31 (UTC) - uint8_t hour; //Hour of Day, range 0..23 (UTC) - uint8_t min; //Minute of Hour, range 0..59 (UTC) - uint8_t sec; //Seconds of Minute, range 0..59 (UTC) - uint8_t valid_flag; //Validity Flags (see ubx documentation) + uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ + uint32_t time_accuracy; /**< Time Accuracy Estimate, ns */ + int32_t time_nanoseconds; /**< Nanoseconds of second, range -1e9 .. 1e9 (UTC) */ + uint16_t year; /**< Year, range 1999..2099 (UTC) */ + uint8_t month; /**< Month, range 1..12 (UTC) */ + uint8_t day; /**< Day of Month, range 1..31 (UTC) */ + uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */ + uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */ + uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */ + uint8_t valid_flag; /**< Validity Flags (see ubx documentation) */ uint8_t ck_a; uint8_t ck_b; } gps_bin_nav_timeutc_packet_t; typedef struct { - uint32_t time_milliseconds; // GPS Millisecond Time of Week - uint16_t gDOP; //Geometric DOP (scaling 0.01) - uint16_t pDOP; //Position DOP (scaling 0.01) - uint16_t tDOP; //Time DOP (scaling 0.01) - uint16_t vDOP; //Vertical DOP (scaling 0.01) - uint16_t hDOP; //Horizontal DOP (scaling 0.01) - uint16_t nDOP; //Northing DOP (scaling 0.01) - uint16_t eDOP; //Easting DOP (scaling 0.01) + uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ + uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */ + uint16_t pDOP; /**< Position DOP (scaling 0.01) */ + uint16_t tDOP; /**< Time DOP (scaling 0.01) */ + uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */ + uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */ + uint16_t nDOP; /**< Northing DOP (scaling 0.01) */ + uint16_t eDOP; /**< Easting DOP (scaling 0.01) */ uint8_t ck_a; uint8_t ck_b; } gps_bin_nav_dop_packet_t; typedef struct { - uint32_t time_milliseconds; // GPS Millisecond Time of Week - uint8_t numCh; //Number of channels + uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ + uint8_t numCh; /**< Number of channels */ uint8_t globalFlags; uint16_t reserved2; } gps_bin_nav_svinfo_part1_packet_t; typedef struct { - uint8_t chn; //Channel number, 255 for SVs not assigned to a channel - uint8_t svid; //Satellite ID + uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */ + uint8_t svid; /**< Satellite ID */ uint8_t flags; uint8_t quality; - uint8_t cno; //Carrier to Noise Ratio (Signal Strength), dbHz - int8_t elev; //Elevation in integer degrees - int16_t azim; //Azimuth in integer degrees - int32_t prRes; //Pseudo range residual in centimetres + uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */ + int8_t elev; /**< Elevation in integer degrees */ + int16_t azim; /**< Azimuth in integer degrees */ + int32_t prRes; /**< Pseudo range residual in centimetres */ } gps_bin_nav_svinfo_part2_packet_t; @@ -192,9 +193,9 @@ typedef struct { } gps_bin_nav_velned_packet_t; //typedef struct { -// int32_t time_milliseconds; // Measurement integer millisecond GPS time of week -// int16_t week; //Measurement GPS week number -// uint8_t numVis; //Number of visible satellites +// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */ +// int16_t week; /**< Measurement GPS week number */ +// uint8_t numVis; /**< Number of visible satellites */ // // //... rest of package is not used in this implementation // @@ -210,7 +211,6 @@ typedef struct { typedef struct { uint8_t clsID; uint8_t msgID; - uint8_t ck_a; uint8_t ck_b; } gps_bin_ack_nak_packet_t; @@ -340,17 +340,27 @@ class UBX : public GPS_Helper public: UBX(); ~UBX(); - - void configure(bool&, bool&, unsigned&, uint8_t*, int&, const unsigned); + void reset(void); + void configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, uint8_t *buffer, int &length, const unsigned max_length); int parse(uint8_t, struct vehicle_gps_position_s*); private: + /** + * Reset the parse state machine for a fresh start + */ void decodeInit(void); + + /** + * While parsing add every byte (except the sync bytes) to the checksum + */ void addByteToChecksum(uint8_t); + + /** + * Add the two checksum bytes to an outgoing message + */ void addChecksumToMessage(uint8_t*, const unsigned); - unsigned _waited; - bool _waiting_for_ack; ubx_config_state_t _config_state; + bool _waiting_for_ack; ubx_decode_state_t _decode_state; uint8_t _rx_buffer[RECV_BUFFER_SIZE]; unsigned _rx_count; From 53c11f87cb9b231cfb9199ce797d983f4e2c6a40 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 4 Feb 2013 17:57:30 -0800 Subject: [PATCH 09/20] Small corrections --- apps/drivers/gps/gps.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 450b3091bd..f4fd7b88e1 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -110,13 +110,13 @@ private: bool _task_should_exit; ///< flag to make the main worker task exit int _serial_fd; ///< serial interface to GPS unsigned _baudrate; ///< current baudrate - unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; ///< try different baudrates that GPS could be set to + const unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; ///< try different baudrates that GPS could be set to volatile int _task; ///< worker task bool _config_needed; ///< flag to signal that configuration of GPS is needed bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed bool _mode_changed; ///< flag that the GPS mode has changed gps_driver_mode_t _mode; ///< current mode - GPS_Helper *_Helper; ///< Class for either UBX, MTK or NMEA helper + GPS_Helper *_Helper; ///< Class for a GPS interface struct vehicle_gps_position_s _report; ///< uORB topic for gps position orb_advert_t _report_pub; ///< uORB pub for gps position float _rate; ///< position update rate From 368ba0056f4a4597c13781b6b5fd6e65930f9fee Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 5 Feb 2013 13:47:31 +0100 Subject: [PATCH 10/20] Added option to select port name, minor tweaks to status printing, sacrificied 20 bytes for better status / user debuggability --- apps/drivers/gps/gps.cpp | 76 +++++++++++++++++++++++++--------------- 1 file changed, 47 insertions(+), 29 deletions(-) diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index f4fd7b88e1..5905db6b82 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -42,6 +42,7 @@ #include #include +#include #include #include #include @@ -93,7 +94,7 @@ static const int ERROR = -1; class GPS : public device::CDev { public: - GPS(); + GPS(const char* uart_path); ~GPS(); virtual int init(); @@ -107,19 +108,20 @@ public: private: - bool _task_should_exit; ///< flag to make the main worker task exit - int _serial_fd; ///< serial interface to GPS - unsigned _baudrate; ///< current baudrate - const unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; ///< try different baudrates that GPS could be set to - volatile int _task; ///< worker task - bool _config_needed; ///< flag to signal that configuration of GPS is needed - bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed - bool _mode_changed; ///< flag that the GPS mode has changed - gps_driver_mode_t _mode; ///< current mode - GPS_Helper *_Helper; ///< Class for a GPS interface - struct vehicle_gps_position_s _report; ///< uORB topic for gps position - orb_advert_t _report_pub; ///< uORB pub for gps position - float _rate; ///< position update rate + bool _task_should_exit; ///< flag to make the main worker task exit + int _serial_fd; ///< serial interface to GPS + unsigned _baudrate; ///< current baudrate + char _port[20]; ///< device / serial port path + const unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; ///< try different baudrates that GPS could be set to + volatile int _task; //< worker task + bool _config_needed; ///< flag to signal that configuration of GPS is needed + bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed + bool _mode_changed; ///< flag that the GPS mode has changed + gps_driver_mode_t _mode; ///< current mode + GPS_Helper *_Helper; ///< instance of GPS parser + struct vehicle_gps_position_s _report; ///< uORB topic for gps position + orb_advert_t _report_pub; ///< uORB pub for gps position + float _rate; ///< position update rate /** @@ -141,7 +143,7 @@ private: /** * Set the baudrate of the UART to the GPS */ - int set_baudrate(unsigned baud); + int set_baudrate(unsigned baud); /** * Send a reset command to the GPS @@ -164,7 +166,7 @@ GPS *g_dev; } -GPS::GPS() : +GPS::GPS(const char* uart_path) : CDev("gps", GPS_DEVICE_PATH), _task_should_exit(false), _baudrates_to_try({9600, 38400, 57600, 115200}), @@ -176,6 +178,11 @@ GPS::GPS() : _report_pub(-1), _rate(0.0f) { + /* store port name */ + strncpy(_port, uart_path, sizeof(_port)); + /* enforce null termination */ + _port[sizeof(_port) - 1] = '\0'; + /* we need this potentially before it could be set in task_main */ g_dev = this; memset(&_report, 0, sizeof(_report)); @@ -198,6 +205,7 @@ GPS::~GPS() if (_task != -1) task_delete(_task); g_dev = nullptr; + } int @@ -302,13 +310,13 @@ GPS::task_main() log("starting"); /* open the serial port */ - _serial_fd = ::open("/dev/ttyS3", O_RDWR); //TODO make the device dynamic depending on startup parameters + _serial_fd = ::open(_port, O_RDWR); //TODO make the device dynamic depending on startup parameters /* buffer to read from the serial port */ uint8_t buf[32]; if (_serial_fd < 0) { - log("failed to open serial port: %d", errno); + log("failed to open serial port: %s err: %d", _port, errno); /* tell the dtor that we are exiting, set error code */ _task = -1; _exit(1); @@ -318,7 +326,6 @@ GPS::task_main() pollfd fds[1]; fds[0].fd = _serial_fd; fds[0].events = POLLIN; - debug("ready"); /* lock against the ioctl handler */ lock(); @@ -418,14 +425,12 @@ GPS::task_main() /* This means something went wrong in the parser, let's reconfigure */ if (!_config_needed) { _config_needed = true; - debug("Lost GPS module"); } config(); } else if (ret_parse > 0) { /* Looks like we got a valid position update, stop configuring and publish it */ if (_config_needed) { _config_needed = false; - debug("Found GPS module"); } /* opportunistic publishing - else invalid data would end up on the bus */ @@ -530,7 +535,7 @@ GPS::print_info() default: break; } - warnx("baudrate: %d, status: %s", _baudrate, (_config_needed) ? "NOT OK" : "OK"); + warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_config_needed) ? "NOT OK" : "OK"); if (_report.timestamp != 0) { warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type, (double)((float)(hrt_absolute_time() - _report.timestamp) / 1000000.0f)); @@ -549,7 +554,7 @@ namespace gps GPS *g_dev; -void start(); +void start(const char *uart_path); void stop(); void test(); void reset(); @@ -559,7 +564,7 @@ void info(); * Start the driver. */ void -start() +start(const char *uart_path) { int fd; @@ -567,7 +572,7 @@ start() errx(1, "already started"); /* create the driver */ - g_dev = new GPS; + g_dev = new GPS(uart_path); if (g_dev == nullptr) goto fail; @@ -644,7 +649,6 @@ info() if (g_dev == nullptr) errx(1, "driver not running"); - printf("state @ %p\n", g_dev); g_dev->print_info(); exit(0); @@ -656,11 +660,24 @@ info() int gps_main(int argc, char *argv[]) { + + /* set to default */ + char* device_name = "/dev/ttyS3"; + /* * Start/load the driver. */ - if (!strcmp(argv[1], "start")) - gps::start(); + if (!strcmp(argv[1], "start")) { + /* work around getopt unreliability */ + if (argc > 3) { + if (!strcmp(argv[2], "-d")) { + device_name = argv[3]; + } else { + goto out; + } + } + gps::start(device_name); + } if (!strcmp(argv[1], "stop")) gps::stop(); @@ -682,5 +699,6 @@ gps_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) gps::info(); - errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status'"); +out: + errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n]"); } From fbbeef7e29cc6aa82e653916b7d5e8005948b815 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 5 Feb 2013 18:54:06 +0100 Subject: [PATCH 11/20] Update on every position change, do not wait for other measurements --- apps/drivers/gps/ubx.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index 66a891da4f..a6f181a735 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -765,11 +765,13 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) /* Add timestamp to finish the report */ gps_position->timestamp = hrt_absolute_time(); /* Reset the flags */ + + /* update on every position change, accept minor delay on other measurements */ _new_nav_posllh = false; - _new_nav_timeutc = false; - _new_nav_dop = false; - _new_nav_sol = false; - _new_nav_velned = false; + // _new_nav_timeutc = false; + // _new_nav_dop = false; + // _new_nav_sol = false; + // _new_nav_velned = false; ret = 1; } From a79ad17f09ac69bf2a19a4f617fa1df16bcaa6be Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 5 Feb 2013 23:16:32 -0800 Subject: [PATCH 12/20] Changed parse interface, differentiation between config needed and position updated, working but might be solved more elegant --- apps/drivers/drv_gps.h | 2 + apps/drivers/gps/gps.cpp | 73 +++++++++++++++++++---------------- apps/drivers/gps/gps_helper.h | 6 +-- apps/drivers/gps/ubx.cpp | 65 ++++++++++++++++--------------- apps/drivers/gps/ubx.h | 4 +- 5 files changed, 81 insertions(+), 69 deletions(-) diff --git a/apps/drivers/drv_gps.h b/apps/drivers/drv_gps.h index 1ae27ed2f9..dfde115eff 100644 --- a/apps/drivers/drv_gps.h +++ b/apps/drivers/drv_gps.h @@ -44,6 +44,8 @@ #include "drv_sensor.h" #include "drv_orb_dev.h" +#define GPS_DEFAULT_UART_PORT "/dev/ttyS3" + #define GPS_DEVICE_PATH "/dev/gps" typedef enum { diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 5905db6b82..28dc949d4b 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -278,7 +278,7 @@ GPS::config() int length = 0; uint8_t send_buffer[SEND_BUFFER_LENGTH]; - _Helper->configure(_config_needed, _baudrate_changed, _baudrate, send_buffer, length, SEND_BUFFER_LENGTH); + _Helper->configure(send_buffer, length, SEND_BUFFER_LENGTH, _baudrate_changed, _baudrate); /* The config message is sent sent at the old baudrate */ if (length > 0) { @@ -339,6 +339,9 @@ GPS::task_main() uint64_t last_rate_measurement = hrt_absolute_time(); unsigned last_rate_count = 0; + bool pos_updated; + bool config_needed_res; + /* loop handling received serial bytes and also configuring in between */ while (!_task_should_exit) { @@ -391,17 +394,17 @@ GPS::task_main() lock(); - - /* this would be bad... */ if (ret < 0) { log("poll error %d", errno); } else if (ret == 0) { - config(); + /* no response from the GPS */ if (_config_needed == false) { _config_needed = true; - warnx("lost GPS module"); + warnx("GPS module timeout"); + _Helper->reset(); } + config(); } else if (ret > 0) { /* if we have new data from GPS, go handle it */ if (fds[0].revents & POLLIN) { @@ -416,39 +419,43 @@ GPS::task_main() /* pass received bytes to the packet decoder */ int j; - int ret_parse = 0; for (j = 0; j < count; j++) { - ret_parse += _Helper->parse(buf[j], &_report); - } + pos_updated = false; + config_needed_res = _config_needed; + _Helper->parse(buf[j], &_report, config_needed_res, pos_updated); + + if (pos_updated) { + /* opportunistic publishing - else invalid data would end up on the bus */ + if (_report_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + } else { + _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } + last_rate_count++; + + /* measure update rate every 5 seconds */ + if (hrt_absolute_time() - last_rate_measurement > 5000000) { + _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f); + last_rate_measurement = hrt_absolute_time(); + last_rate_count = 0; + } - if (ret_parse < 0) { - /* This means something went wrong in the parser, let's reconfigure */ - if (!_config_needed) { - _config_needed = true; } - config(); - } else if (ret_parse > 0) { - /* Looks like we got a valid position update, stop configuring and publish it */ - if (_config_needed) { + if (config_needed_res == true && _config_needed == false) { + /* the parser told us that an error happened and reconfiguration is needed */ + _config_needed = true; + warnx("GPS module lost"); + _Helper->reset(); + config(); + } else if (config_needed_res == true && _config_needed == true) { + /* we are still configuring */ + config(); + } else if (config_needed_res == false && _config_needed == true) { + /* the parser is happy, stop configuring */ + warnx("GPS module found"); _config_needed = false; } - - /* opportunistic publishing - else invalid data would end up on the bus */ - if (_report_pub > 0) { - orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); - } else { - _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); - } - last_rate_count++; - - /* measure update rate every 5 seconds */ - if (hrt_absolute_time() - last_rate_measurement > 5000000) { - _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f); - last_rate_measurement = hrt_absolute_time(); - last_rate_count = 0; - } } - /* else if ret_parse == 0: just keep parsing */ } } } @@ -662,7 +669,7 @@ gps_main(int argc, char *argv[]) { /* set to default */ - char* device_name = "/dev/ttyS3"; + char* device_name = GPS_DEFAULT_UART_PORT; /* * Start/load the driver. diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h index 8a6b0148b7..176b7eba81 100644 --- a/apps/drivers/gps/gps_helper.h +++ b/apps/drivers/gps/gps_helper.h @@ -40,9 +40,9 @@ class GPS_Helper { public: - virtual void reset() = 0; - virtual void configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, uint8_t *buffer, int &length, const unsigned max_length) = 0; - virtual int parse(uint8_t b, struct vehicle_gps_position_s *gps_position) = 0; + virtual void reset(void) = 0; + virtual void configure(uint8_t *buffer, int &length, const unsigned max_length, bool &baudrate_changed, unsigned &baudrate) = 0; + virtual void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated) = 0; }; #endif /* GPS_HELPER_H */ diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index a6f181a735..440ec74c58 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -72,7 +72,7 @@ UBX::reset() } void -UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, uint8_t *buffer, int &length, const unsigned max_length) +UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &baudrate_changed, unsigned &baudrate) { /* make sure the buffer, where the message is written to, is long enough */ assert(sizeof(type_gps_bin_cfg_prt_packet_t)+2 <= max_length); @@ -84,9 +84,10 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, if (!_waiting_for_ack) { _waiting_for_ack = true; if (_config_state == UBX_CONFIG_STATE_CONFIGURED) { - config_needed = false; - length = 0; - _config_state = UBX_CONFIG_STATE_PRT; /* set the state for next time */ + /* This should never happen, the parser should set the flag, + * if it should be reconfigured, reset() should be called first. + */ + warnx("ubx: already configured"); _waiting_for_ack = false; return; } else if (_config_state == UBX_CONFIG_STATE_PRT) { @@ -246,12 +247,9 @@ UBX::configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, } } -int -UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) +void +UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_needed, bool &pos_updated) { - /* if no error happens and no new report is ready yet, ret will stay 0 */ - int ret = 0; - switch (_decode_state) { /* First, look for sync1 */ case UBX_DECODE_UNINIT: @@ -382,7 +380,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) default: //should not happen because we set the class warnx("UBX Error, we set a class that we don't know"); decodeInit(); - ret = -1; + config_needed = true; break; } break; @@ -417,7 +415,12 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) gps_position->counter_pos_valid++; gps_position->counter++; + /* Add timestamp to finish the report */ + gps_position->timestamp = hrt_absolute_time(); + _new_nav_posllh = true; + /* set flag to trigger publishing of new position */ + pos_updated = true; } else { warnx("NAV_POSLLH: checksum invalid"); @@ -436,11 +439,13 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { gps_position->fix_type = packet->gpsFix; - - gps_position->counter++; gps_position->s_variance = packet->sAcc; gps_position->p_variance = packet->pAcc; + gps_position->counter++; + gps_position->timestamp = hrt_absolute_time(); + + _new_nav_sol = true; } else { @@ -463,6 +468,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) gps_position->epv = packet->vDOP; gps_position->counter++; + gps_position->timestamp = hrt_absolute_time(); _new_nav_dop = true; @@ -496,6 +502,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); gps_position->counter++; + gps_position->timestamp = hrt_absolute_time(); _new_nav_timeutc = true; @@ -587,6 +594,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) gps_position->satellites_visible = satellites_used++; // visible ~= used but we are interested in the used ones gps_position->counter++; + gps_position->timestamp = hrt_absolute_time(); // as this message arrives only with 1Hz and is not essential, we don't take it into account for the report @@ -614,6 +622,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) gps_position->cog = (uint16_t)((float)(packet->heading) * 1e-3f); gps_position->counter++; + gps_position->timestamp = hrt_absolute_time(); _new_nav_velned = true; @@ -647,8 +656,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) // // // Reset state machine to decode next packet // decodeInit(); -// return ret; -// // break; // } @@ -701,6 +708,8 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) case UBX_CONFIG_STATE_MSG_NAV_VELNED: if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) _config_state = UBX_CONFIG_STATE_CONFIGURED; + /* set the flag to tell the driver that configuration was successful */ + config_needed = false; break; // case UBX_CONFIG_STATE_MSG_RXM_SVSI: // if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) @@ -715,7 +724,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) // Reset state machine to decode next packet decodeInit(); - break; } @@ -727,16 +735,14 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { warnx("UBX: Received: Not Acknowledged"); - ret = 1; - + /* configuration obviously not successful */ + config_needed = true; } else { warnx("ACK_NAK: checksum invalid\n"); } // Reset state machine to decode next packet decodeInit(); - return ret; - break; } @@ -752,7 +758,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) } else { warnx("buffer full, restarting"); decodeInit(); - ret = -1; + config_needed = true; } break; default: @@ -762,21 +768,18 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position) /* return 1 when position updates and the remaining packets updated at least once */ if(_new_nav_posllh &&_new_nav_timeutc && _new_nav_dop && _new_nav_sol && _new_nav_velned) { - /* Add timestamp to finish the report */ - gps_position->timestamp = hrt_absolute_time(); + /* we have received everything, this most probably means that the configuration is fine */ + config_needed = false; + /* Reset the flags */ - - /* update on every position change, accept minor delay on other measurements */ _new_nav_posllh = false; - // _new_nav_timeutc = false; - // _new_nav_dop = false; - // _new_nav_sol = false; - // _new_nav_velned = false; + _new_nav_timeutc = false; + _new_nav_dop = false; + _new_nav_sol = false; + _new_nav_velned = false; - ret = 1; } - - return ret; + return; } void diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index 0cac10f0a3..d3c6c6d4cf 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -341,8 +341,8 @@ public: UBX(); ~UBX(); void reset(void); - void configure(bool &config_needed, bool &baudrate_changed, unsigned &baudrate, uint8_t *buffer, int &length, const unsigned max_length); - int parse(uint8_t, struct vehicle_gps_position_s*); + void configure(uint8_t *buffer, int &length, const unsigned max_length, bool &baudrate_changed, unsigned &baudrate); + void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated); private: /** From fc4be3e7280db480b67b7c6cec11e35481969bbb Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 6 Feb 2013 12:41:05 -0800 Subject: [PATCH 13/20] Changed gps position topic mostly to SI units and float, removed counters and added specifig timestamps --- apps/commander/commander.c | 14 +-- apps/drivers/gps/gps.cpp | 4 +- apps/drivers/gps/ubx.cpp | 110 ++++++++++++------------ apps/drivers/gps/ubx.h | 30 +++---- apps/examples/kalman_demo/KalmanNav.cpp | 23 ++--- apps/mavlink/mavlink_receiver.c | 24 +++--- apps/mavlink/orb_listener.c | 10 +-- apps/uORB/topics/home_position.h | 8 +- apps/uORB/topics/vehicle_gps_position.h | 55 ++++++------ 9 files changed, 139 insertions(+), 139 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 3a6fecf746..f19f1d0e6f 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1678,8 +1678,8 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position); /* check for first, long-term and valid GPS lock -> set home position */ - float hdop_m = gps_position.eph / 100.0f; - float vdop_m = gps_position.epv / 100.0f; + float hdop_m = gps_position.eph_m; + float vdop_m = gps_position.epv_m; /* check if gps fix is ok */ // XXX magic number @@ -1697,7 +1697,7 @@ int commander_thread_main(int argc, char *argv[]) if (gps_position.fix_type == GPS_FIX_TYPE_3D && (hdop_m < dop_threshold_m) && (vdop_m < dop_threshold_m) && !home_position_set - && (hrt_absolute_time() - gps_position.timestamp < 2000000) + && (hrt_absolute_time() - gps_position.timestamp_position < 2000000) && !current_status.flag_system_armed) { warnx("setting home position"); @@ -1706,11 +1706,11 @@ int commander_thread_main(int argc, char *argv[]) home.lon = gps_position.lon; home.alt = gps_position.alt; - home.eph = gps_position.eph; - home.epv = gps_position.epv; + home.eph_m = gps_position.eph_m; + home.epv_m = gps_position.epv_m; - home.s_variance = gps_position.s_variance; - home.p_variance = gps_position.p_variance; + home.s_variance_m_s = gps_position.s_variance_m_s; + home.p_variance_m = gps_position.p_variance_m; /* announce new home position */ if (home_pub > 0) { diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 28dc949d4b..8c2775adbb 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -543,9 +543,9 @@ GPS::print_info() break; } warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_config_needed) ? "NOT OK" : "OK"); - if (_report.timestamp != 0) { + if (_report.timestamp_position != 0) { warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type, - (double)((float)(hrt_absolute_time() - _report.timestamp) / 1000000.0f)); + (double)((float)(hrt_absolute_time() - _report.timestamp_position) / 1000000.0f)); warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt); warnx("update rate: %6.2f Hz", (double)_rate); } diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index 440ec74c58..eec1df9809 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -37,6 +37,7 @@ #include #include +#include #include #include #include @@ -52,7 +53,7 @@ _config_state(UBX_CONFIG_STATE_PRT), _waiting_for_ack(false), _new_nav_posllh(false), _new_nav_timeutc(false), -_new_nav_dop(false), +//_new_nav_dop(false), _new_nav_sol(false), _new_nav_velned(false) { @@ -211,10 +212,10 @@ UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &ba cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC; break; - case UBX_CONFIG_STATE_MSG_NAV_DOP: - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP; - break; +// case UBX_CONFIG_STATE_MSG_NAV_DOP: +// cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; +// cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP; +// break; case UBX_CONFIG_STATE_MSG_NAV_SVINFO: cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO; @@ -316,10 +317,10 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ _message_id = NAV_TIMEUTC; break; - case UBX_MESSAGE_NAV_DOP: - _decode_state = UBX_DECODE_GOT_MESSAGEID; - _message_id = NAV_DOP; - break; +// case UBX_MESSAGE_NAV_DOP: +// _decode_state = UBX_DECODE_GOT_MESSAGEID; +// _message_id = NAV_DOP; +// break; case UBX_MESSAGE_NAV_SVINFO: _decode_state = UBX_DECODE_GOT_MESSAGEID; @@ -412,11 +413,11 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ gps_position->lon = packet->lon; gps_position->alt = packet->height_msl; - gps_position->counter_pos_valid++; - gps_position->counter++; + gps_position->eph_m = (float)packet->hAcc * 1e-2f; // from mm to m + gps_position->epv_m = (float)packet->vAcc * 1e-2f; // from mm to m /* Add timestamp to finish the report */ - gps_position->timestamp = hrt_absolute_time(); + gps_position->timestamp_position = hrt_absolute_time(); _new_nav_posllh = true; /* set flag to trigger publishing of new position */ @@ -439,11 +440,10 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { gps_position->fix_type = packet->gpsFix; - gps_position->s_variance = packet->sAcc; - gps_position->p_variance = packet->pAcc; + gps_position->s_variance_m_s = packet->sAcc; + gps_position->p_variance_m = packet->pAcc; - gps_position->counter++; - gps_position->timestamp = hrt_absolute_time(); + gps_position->timestamp_variance = hrt_absolute_time(); _new_nav_sol = true; @@ -457,29 +457,28 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ break; } - case NAV_DOP: { -// printf("GOT NAV_DOP MESSAGE\n"); - gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer; - - //Check if checksum is valid and the store the gps information - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - - gps_position->eph = packet->hDOP; - gps_position->epv = packet->vDOP; - - gps_position->counter++; - gps_position->timestamp = hrt_absolute_time(); - - _new_nav_dop = true; - - } else { - warnx("NAV_DOP: checksum invalid"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; - } +// case NAV_DOP: { +//// printf("GOT NAV_DOP MESSAGE\n"); +// gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer; +// +// //Check if checksum is valid and the store the gps information +// if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { +// +// gps_position->eph_m = packet->hDOP; +// gps_position->epv = packet->vDOP; +// +// gps_position->timestamp_posdilution = hrt_absolute_time(); +// +// _new_nav_dop = true; +// +// } else { +// warnx("NAV_DOP: checksum invalid"); +// } +// +// // Reset state machine to decode next packet +// decodeInit(); +// break; +// } case NAV_TIMEUTC: { // printf("GOT NAV_TIMEUTC MESSAGE\n"); @@ -501,8 +500,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); - gps_position->counter++; - gps_position->timestamp = hrt_absolute_time(); + gps_position->timestamp_time = hrt_absolute_time(); _new_nav_timeutc = true; @@ -593,8 +591,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ } gps_position->satellites_visible = satellites_used++; // visible ~= used but we are interested in the used ones - gps_position->counter++; - gps_position->timestamp = hrt_absolute_time(); + gps_position->timestamp_satellites = hrt_absolute_time(); // as this message arrives only with 1Hz and is not essential, we don't take it into account for the report @@ -614,18 +611,17 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ //Check if checksum is valid and the store the gps information if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - gps_position->vel = (uint16_t)packet->speed; - gps_position->vel_n = packet->velN / 100.0f; - gps_position->vel_e = packet->velE / 100.0f; - gps_position->vel_d = packet->velD / 100.0f; + gps_position->vel_m_s = (float)packet->speed * 1e-2f; + gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; + gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; + gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; + gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f; gps_position->vel_ned_valid = true; - gps_position->cog = (uint16_t)((float)(packet->heading) * 1e-3f); - - gps_position->counter++; - gps_position->timestamp = hrt_absolute_time(); + gps_position->timestamp_velocity = hrt_absolute_time(); _new_nav_velned = true; + } else { warnx("NAV_VELNED: checksum invalid"); } @@ -690,13 +686,13 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ _config_state = UBX_CONFIG_STATE_MSG_NAV_TIMEUTC; break; case UBX_CONFIG_STATE_MSG_NAV_TIMEUTC: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) - _config_state = UBX_CONFIG_STATE_MSG_NAV_DOP; - break; - case UBX_CONFIG_STATE_MSG_NAV_DOP: if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) _config_state = UBX_CONFIG_STATE_MSG_NAV_SVINFO; break; +// case UBX_CONFIG_STATE_MSG_NAV_DOP: +// if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) +// _config_state = UBX_CONFIG_STATE_MSG_NAV_SVINFO; +// break; case UBX_CONFIG_STATE_MSG_NAV_SVINFO: if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) _config_state = UBX_CONFIG_STATE_MSG_NAV_SOL; @@ -766,7 +762,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ } /* return 1 when position updates and the remaining packets updated at least once */ - if(_new_nav_posllh &&_new_nav_timeutc && _new_nav_dop && _new_nav_sol && _new_nav_velned) { + if(_new_nav_posllh &&_new_nav_timeutc /*&& _new_nav_dop*/ && _new_nav_sol && _new_nav_velned) { /* we have received everything, this most probably means that the configuration is fine */ config_needed = false; @@ -774,7 +770,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ /* Reset the flags */ _new_nav_posllh = false; _new_nav_timeutc = false; - _new_nav_dop = false; +// _new_nav_dop = false; _new_nav_sol = false; _new_nav_velned = false; diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index d3c6c6d4cf..43cded02f7 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -54,7 +54,7 @@ #define UBX_MESSAGE_NAV_POSLLH 0x02 #define UBX_MESSAGE_NAV_SOL 0x06 #define UBX_MESSAGE_NAV_TIMEUTC 0x21 -#define UBX_MESSAGE_NAV_DOP 0x04 +//#define UBX_MESSAGE_NAV_DOP 0x04 #define UBX_MESSAGE_NAV_SVINFO 0x30 #define UBX_MESSAGE_NAV_VELNED 0x12 //#define UBX_MESSAGE_RXM_SVSI 0x20 @@ -140,18 +140,18 @@ typedef struct { uint8_t ck_b; } gps_bin_nav_timeutc_packet_t; -typedef struct { - uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ - uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */ - uint16_t pDOP; /**< Position DOP (scaling 0.01) */ - uint16_t tDOP; /**< Time DOP (scaling 0.01) */ - uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */ - uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */ - uint16_t nDOP; /**< Northing DOP (scaling 0.01) */ - uint16_t eDOP; /**< Easting DOP (scaling 0.01) */ - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_nav_dop_packet_t; +//typedef struct { +// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ +// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */ +// uint16_t pDOP; /**< Position DOP (scaling 0.01) */ +// uint16_t tDOP; /**< Time DOP (scaling 0.01) */ +// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */ +// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */ +// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */ +// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */ +// uint8_t ck_a; +// uint8_t ck_b; +//} gps_bin_nav_dop_packet_t; typedef struct { uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ @@ -311,7 +311,7 @@ typedef enum { NAV_POSLLH, NAV_SOL, NAV_TIMEUTC, - NAV_DOP, +// NAV_DOP, NAV_SVINFO, NAV_VELNED, // RXM_SVSI, @@ -371,7 +371,7 @@ private: unsigned _payload_size; bool _new_nav_posllh; bool _new_nav_timeutc; - bool _new_nav_dop; +// bool _new_nav_dop; bool _new_nav_sol; bool _new_nav_velned; }; diff --git a/apps/examples/kalman_demo/KalmanNav.cpp b/apps/examples/kalman_demo/KalmanNav.cpp index 7e89dffb20..b7f651d8a6 100644 --- a/apps/examples/kalman_demo/KalmanNav.cpp +++ b/apps/examples/kalman_demo/KalmanNav.cpp @@ -190,11 +190,12 @@ void KalmanNav::update() if (!_positionInitialized && _attitudeInitialized && // wait for attitude first gpsUpdate && - _gps.fix_type > 2 && - _gps.counter_pos_valid > 10) { - vN = _gps.vel_n; - vE = _gps.vel_e; - vD = _gps.vel_d; + _gps.fix_type > 2 + //&& _gps.counter_pos_valid > 10 + ) { + vN = _gps.vel_n_m_s; + vE = _gps.vel_e_m_s; + vD = _gps.vel_d_m_s; setLatDegE7(_gps.lat); setLonDegE7(_gps.lon); setAltE3(_gps.alt); @@ -259,7 +260,7 @@ void KalmanNav::updatePublications() // position publication _pos.timestamp = _pubTimeStamp; - _pos.time_gps_usec = _gps.timestamp; + _pos.time_gps_usec = _gps.timestamp_position; _pos.valid = true; _pos.lat = getLatDegE7(); _pos.lon = getLonDegE7(); @@ -631,8 +632,8 @@ int KalmanNav::correctPos() // residual Vector y(5); - y(0) = _gps.vel_n - vN; - y(1) = _gps.vel_e - vE; + y(0) = _gps.vel_n_m_s - vN; + y(1) = _gps.vel_e_m_s - vE; y(2) = double(_gps.lat) - lat * 1.0e7 * M_RAD_TO_DEG; y(3) = double(_gps.lon) - lon * 1.0e7 * M_RAD_TO_DEG; y(4) = double(_gps.alt) / 1.0e3 - alt; @@ -651,9 +652,9 @@ int KalmanNav::correctPos() // abort correction and return printf("[kalman_demo] numerical failure in gps correction\n"); // fallback to GPS - vN = _gps.vel_n; - vE = _gps.vel_e; - vD = _gps.vel_d; + vN = _gps.vel_n_m_s; + vE = _gps.vel_e_m_s; + vD = _gps.vel_d_m_s; setLatDegE7(_gps.lat); setLonDegE7(_gps.lon); setAltE3(_gps.alt); diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index 86732d07c0..b3b4b1e0b2 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -387,22 +387,22 @@ handle_message(mavlink_message_t *msg) static uint64_t old_timestamp = 0; /* gps */ - hil_gps.timestamp = gps.time_usec; - hil_gps.counter = hil_counter++; + hil_gps.timestamp_position = gps.time_usec; +// hil_gps.counter = hil_counter++; hil_gps.time_gps_usec = gps.time_usec; hil_gps.lat = gps.lat; hil_gps.lon = gps.lon; hil_gps.alt = gps.alt; - hil_gps.counter_pos_valid = hil_counter++; - hil_gps.eph = gps.eph; - hil_gps.epv = gps.epv; - hil_gps.s_variance = 100; - hil_gps.p_variance = 100; - hil_gps.vel = gps.vel; - hil_gps.vel_n = gps.vel / 100.0f * cosf(gps.cog / M_RAD_TO_DEG_F / 100.0f); - hil_gps.vel_e = gps.vel / 100.0f * sinf(gps.cog / M_RAD_TO_DEG_F / 100.0f); - hil_gps.vel_d = 0.0f; - hil_gps.cog = gps.cog; +// hil_gps.counter_pos_valid = hil_counter++; + hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m + hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m + hil_gps.s_variance_m_s = 100; // XXX 100 m/s variance? + hil_gps.p_variance_m = 100; // XXX 100 m variance? + hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s + hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(gps.cog * M_DEG_TO_RAD_F * 1e-2f); + hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(gps.cog * M_DEG_TO_RAD_F * 1e-2f); + hil_gps.vel_d_m_s = 0.0f; + hil_gps.cog_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; // from deg*100 to rad hil_gps.fix_type = gps.fix_type; hil_gps.satellites_visible = gps.satellites_visible; diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index 18da70f610..9f85d5801f 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -231,15 +231,15 @@ l_vehicle_gps_position(struct listener *l) /* GPS position */ mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0, - gps.timestamp, + gps.timestamp_position, gps.fix_type, gps.lat, gps.lon, gps.alt, - gps.eph, - gps.epv, - gps.vel, - gps.cog, + (uint16_t)(gps.eph_m * 1e2f), // from m to cm + (uint16_t)(gps.epv_m * 1e2f), // from m to cm + (uint16_t)(gps.vel_m_s * 1e2f), // from m/s to cm/s + (uint16_t)(gps.cog_rad * M_RAD_TO_DEG_F * 1e2f), // from rad to deg * 100 gps.satellites_visible); if (gps.satellite_info_available && (gps_counter % 4 == 0)) { diff --git a/apps/uORB/topics/home_position.h b/apps/uORB/topics/home_position.h index dec34b6ab4..7e1b82a0fb 100644 --- a/apps/uORB/topics/home_position.h +++ b/apps/uORB/topics/home_position.h @@ -61,10 +61,10 @@ struct home_position_s int32_t lat; /**< Latitude in 1E7 degrees */ int32_t lon; /**< Longitude in 1E7 degrees */ int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */ - uint16_t eph; /**< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 */ - uint16_t epv; /**< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 */ - float s_variance; /**< speed accuracy estimate cm/s */ - float p_variance; /**< position accuracy estimate cm */ + float eph_m; /**< GPS HDOP horizontal dilution of position in m */ + float epv_m; /**< GPS VDOP horizontal dilution of position in m */ + float s_variance_m_s; /**< speed accuracy estimate m/s */ + float p_variance_m; /**< position accuracy estimate m */ }; /** diff --git a/apps/uORB/topics/vehicle_gps_position.h b/apps/uORB/topics/vehicle_gps_position.h index db529da06d..aa75c22acb 100644 --- a/apps/uORB/topics/vehicle_gps_position.h +++ b/apps/uORB/topics/vehicle_gps_position.h @@ -55,35 +55,38 @@ */ struct vehicle_gps_position_s { - uint64_t timestamp; /**< Timestamp (microseconds since system boot) */ - uint32_t counter; /**< Count of GPS messages */ - uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */ + uint64_t timestamp_position; /**< Timestamp for position information */ + int32_t lat; /**< Latitude in 1E7 degrees */ + int32_t lon; /**< Longitude in 1E7 degrees */ + int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */ - int32_t lat; /**< Latitude in 1E7 degrees //LOGME */ - int32_t lon; /**< Longitude in 1E7 degrees //LOGME */ - int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL //LOGME */ - uint16_t counter_pos_valid; /**< is only increased when new lat/lon/alt information was added */ - uint16_t eph; /**< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 //LOGME */ - uint16_t epv; /**< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 */ - float s_variance; /**< speed accuracy estimate cm/s */ - float p_variance; /**< position accuracy estimate cm */ - uint16_t vel; /**< GPS ground speed (m/s * 100). If unknown, set to: 65535 */ - float vel_n; /**< GPS ground speed in m/s */ - float vel_e; /**< GPS ground speed in m/s */ - float vel_d; /**< GPS ground speed in m/s */ - uint16_t cog; /**< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 */ - uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ - uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */ + uint64_t timestamp_variance; + float s_variance_m_s; /**< speed accuracy estimate m/s */ + float p_variance_m; /**< position accuracy estimate m */ + uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ - uint8_t satellite_prn[20]; /**< Global satellite ID */ - uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */ - uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ - uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ - uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */ - uint8_t satellite_info_available; /**< 0 for no info, 1 for info available */ + float eph_m; /**< GPS HDOP horizontal dilution of position in m */ + float epv_m; /**< GPS VDOP horizontal dilution of position in m */ - /* flags */ - float vel_ned_valid; /**< Flag to indicate if NED speed is valid */ + uint64_t timestamp_velocity; /**< Timestamp for velocity informations */ + float vel_m_s; /**< GPS ground speed (m/s) */ + float vel_n_m_s; /**< GPS ground speed in m/s */ + float vel_e_m_s; /**< GPS ground speed in m/s */ + float vel_d_m_s; /**< GPS ground speed in m/s */ + float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad */ + bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */ + + uint64_t timestamp_time; /**< Timestamp for time information */ + uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */ + + uint64_t timestamp_satellites; /**< Timestamp for sattelite information */ + uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */ + uint8_t satellite_prn[20]; /**< Global satellite ID */ + uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */ + uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ + uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ + uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */ + uint8_t satellite_info_available; /**< 0 for no info, 1 for info available */ }; /** From d962e6c403678e14a64a6b01be8773e98660bb24 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 6 Feb 2013 13:50:32 -0800 Subject: [PATCH 14/20] Removed some unnecessairy flags, home position back working --- apps/commander/commander.c | 9 +++-- apps/drivers/gps/gps.cpp | 2 +- apps/drivers/gps/ubx.cpp | 49 ++++--------------------- apps/drivers/gps/ubx.h | 5 --- apps/uORB/topics/vehicle_gps_position.h | 2 +- 5 files changed, 16 insertions(+), 51 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index f19f1d0e6f..6b1bc0f9b5 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -1683,7 +1683,8 @@ int commander_thread_main(int argc, char *argv[]) /* check if gps fix is ok */ // XXX magic number - float dop_threshold_m = 2.0f; + float hdop_threshold_m = 4.0f; + float vdop_threshold_m = 8.0f; /* * If horizontal dilution of precision (hdop / eph) @@ -1694,8 +1695,10 @@ int commander_thread_main(int argc, char *argv[]) * the system is currently not armed, set home * position to the current position. */ - if (gps_position.fix_type == GPS_FIX_TYPE_3D && (hdop_m < dop_threshold_m) - && (vdop_m < dop_threshold_m) + + if (gps_position.fix_type == GPS_FIX_TYPE_3D + && (hdop_m < hdop_threshold_m) + && (vdop_m < vdop_threshold_m) && !home_position_set && (hrt_absolute_time() - gps_position.timestamp_position < 2000000) && !current_status.flag_system_armed) { diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 8c2775adbb..45f18158fb 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -591,7 +591,7 @@ start(const char *uart_path) fd = open(GPS_DEVICE_PATH, O_RDONLY); if (fd < 0) { - printf("Could not open device path: %s\n", GPS_DEVICE_PATH); + errx(1, "Could not open device path: %s\n", GPS_DEVICE_PATH); goto fail; } exit(0); diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index eec1df9809..a823271758 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -50,12 +50,7 @@ UBX::UBX() : _config_state(UBX_CONFIG_STATE_PRT), -_waiting_for_ack(false), -_new_nav_posllh(false), -_new_nav_timeutc(false), -//_new_nav_dop(false), -_new_nav_sol(false), -_new_nav_velned(false) +_waiting_for_ack(false) { reset(); } @@ -413,13 +408,12 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ gps_position->lon = packet->lon; gps_position->alt = packet->height_msl; - gps_position->eph_m = (float)packet->hAcc * 1e-2f; // from mm to m - gps_position->epv_m = (float)packet->vAcc * 1e-2f; // from mm to m + gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m + gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m /* Add timestamp to finish the report */ gps_position->timestamp_position = hrt_absolute_time(); - _new_nav_posllh = true; /* set flag to trigger publishing of new position */ pos_updated = true; @@ -445,9 +439,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ gps_position->timestamp_variance = hrt_absolute_time(); - - _new_nav_sol = true; - } else { warnx("NAV_SOL: checksum invalid"); } @@ -502,8 +493,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ gps_position->timestamp_time = hrt_absolute_time(); - _new_nav_timeutc = true; - } else { warnx("NAV_TIMEUTC: checksum invalid"); } @@ -581,20 +570,16 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ gps_position->satellite_elevation[i] = 0; gps_position->satellite_azimuth[i] = 0; } + gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones - /* set flag if any sat info is available */ - if (!packet_part1->numCh > 0) { - gps_position->satellite_info_available = 1; - + /* set timestamp if any sat info is available */ + if (packet_part1->numCh > 0) { + gps_position->satellite_info_available = true; } else { - gps_position->satellite_info_available = 0; + gps_position->satellite_info_available = false; } - - gps_position->satellites_visible = satellites_used++; // visible ~= used but we are interested in the used ones gps_position->timestamp_satellites = hrt_absolute_time(); - // as this message arrives only with 1Hz and is not essential, we don't take it into account for the report - } else { warnx("NAV_SVINFO: checksum invalid"); } @@ -619,9 +604,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ gps_position->vel_ned_valid = true; gps_position->timestamp_velocity = hrt_absolute_time(); - _new_nav_velned = true; - - } else { warnx("NAV_VELNED: checksum invalid"); } @@ -760,21 +742,6 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ default: break; } - - /* return 1 when position updates and the remaining packets updated at least once */ - if(_new_nav_posllh &&_new_nav_timeutc /*&& _new_nav_dop*/ && _new_nav_sol && _new_nav_velned) { - - /* we have received everything, this most probably means that the configuration is fine */ - config_needed = false; - - /* Reset the flags */ - _new_nav_posllh = false; - _new_nav_timeutc = false; -// _new_nav_dop = false; - _new_nav_sol = false; - _new_nav_velned = false; - - } return; } diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index 43cded02f7..a23bb55025 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -369,11 +369,6 @@ private: ubx_message_class_t _message_class; ubx_message_id_t _message_id; unsigned _payload_size; - bool _new_nav_posllh; - bool _new_nav_timeutc; -// bool _new_nav_dop; - bool _new_nav_sol; - bool _new_nav_velned; }; #endif /* UBX_H_ */ diff --git a/apps/uORB/topics/vehicle_gps_position.h b/apps/uORB/topics/vehicle_gps_position.h index aa75c22acb..5463a460da 100644 --- a/apps/uORB/topics/vehicle_gps_position.h +++ b/apps/uORB/topics/vehicle_gps_position.h @@ -86,7 +86,7 @@ struct vehicle_gps_position_s uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */ - uint8_t satellite_info_available; /**< 0 for no info, 1 for info available */ + bool satellite_info_available; /**< 0 for no info, 1 for info available */ }; /** From 6ed5d97aea29a284015708a6089b7910afea8369 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 6 Feb 2013 18:47:32 -0800 Subject: [PATCH 15/20] Merged mtk16 and mtk19 helper classes, configure() now writes directly instead of buffering --- apps/drivers/drv_gps.h | 13 +------- apps/drivers/gps/gps.cpp | 53 ++++-------------------------- apps/drivers/gps/gps_helper.h | 3 +- apps/drivers/gps/ubx.cpp | 62 ++++++++++++++--------------------- apps/drivers/gps/ubx.h | 11 +++++-- 5 files changed, 41 insertions(+), 101 deletions(-) diff --git a/apps/drivers/drv_gps.h b/apps/drivers/drv_gps.h index dfde115eff..67248efcd9 100644 --- a/apps/drivers/drv_gps.h +++ b/apps/drivers/drv_gps.h @@ -50,8 +50,7 @@ typedef enum { GPS_DRIVER_MODE_UBX = 0, - GPS_DRIVER_MODE_MTK19, - GPS_DRIVER_MODE_MTK16, + GPS_DRIVER_MODE_MTK, GPS_DRIVER_MODE_NMEA, } gps_driver_mode_t; @@ -67,14 +66,4 @@ ORB_DECLARE(gps); #define _GPSIOCBASE (0x2800) //TODO: arbitrary choice... #define _GPSIOC(_n) (_IOC(_GPSIOCBASE, _n)) -/** configure ubx mode */ -#define GPS_CONFIGURE_UBX _GPSIOC(0) - -/** configure mtk mode */ -#define GPS_CONFIGURE_MTK19 _GPSIOC(1) -#define GPS_CONFIGURE_MTK16 _GPSIOC(2) - -/** configure mtk mode */ -#define GPS_CONFIGURE_NMEA _GPSIOC(3) - #endif /* _DRV_GPS_H */ diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 45f18158fb..3e1aca810c 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -72,6 +72,7 @@ #include #include "ubx.h" +#include "mtk.h" #define SEND_BUFFER_LENGTH 100 #define TIMEOUT 1000000 //1s @@ -238,30 +239,6 @@ GPS::ioctl(struct file *filp, int cmd, unsigned long arg) int ret = OK; switch (cmd) { - case GPS_CONFIGURE_UBX: - if (_mode != GPS_DRIVER_MODE_UBX) { - _mode = GPS_DRIVER_MODE_UBX; - _mode_changed = true; - } - break; - case GPS_CONFIGURE_MTK19: - if (_mode != GPS_DRIVER_MODE_MTK19) { - _mode = GPS_DRIVER_MODE_MTK19; - _mode_changed = true; - } - break; - case GPS_CONFIGURE_MTK16: - if (_mode != GPS_DRIVER_MODE_MTK16) { - _mode = GPS_DRIVER_MODE_MTK16; - _mode_changed = true; - } - break; - case GPS_CONFIGURE_NMEA: - if (_mode != GPS_DRIVER_MODE_NMEA) { - _mode = GPS_DRIVER_MODE_NMEA; - _mode_changed = true; - } - break; case SENSORIOCRESET: cmd_reset(); break; @@ -275,19 +252,7 @@ GPS::ioctl(struct file *filp, int cmd, unsigned long arg) void GPS::config() { - int length = 0; - uint8_t send_buffer[SEND_BUFFER_LENGTH]; - - _Helper->configure(send_buffer, length, SEND_BUFFER_LENGTH, _baudrate_changed, _baudrate); - - /* The config message is sent sent at the old baudrate */ - if (length > 0) { - - if (length != ::write(_serial_fd, send_buffer, length)) { - debug("write config failed"); - return; - } - } + _Helper->configure(_serial_fd, _baudrate_changed, _baudrate); /* Sometimes the baudrate needs to be changed, for instance UBX with factory settings are changed * from 9600 to 38400 @@ -356,11 +321,8 @@ GPS::task_main() case GPS_DRIVER_MODE_UBX: _Helper = new UBX(); break; - case GPS_DRIVER_MODE_MTK19: - //_Helper = new MTK19(); - break; - case GPS_DRIVER_MODE_MTK16: - //_Helper = new MTK16(); + case GPS_DRIVER_MODE_MTK: + _Helper = new MTK(); break; case GPS_DRIVER_MODE_NMEA: //_Helper = new NMEA(); @@ -530,11 +492,8 @@ GPS::print_info() case GPS_DRIVER_MODE_UBX: warnx("protocol: UBX"); break; - case GPS_DRIVER_MODE_MTK19: - warnx("protocol: MTK 1.9"); - break; - case GPS_DRIVER_MODE_MTK16: - warnx("protocol: MTK 1.6"); + case GPS_DRIVER_MODE_MTK: + warnx("protocol: MTK"); break; case GPS_DRIVER_MODE_NMEA: warnx("protocol: NMEA"); diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h index 176b7eba81..576692c2a4 100644 --- a/apps/drivers/gps/gps_helper.h +++ b/apps/drivers/gps/gps_helper.h @@ -36,12 +36,13 @@ /* @file U-Blox protocol definitions */ #ifndef GPS_HELPER_H +#define GPS_HELPER_H class GPS_Helper { public: virtual void reset(void) = 0; - virtual void configure(uint8_t *buffer, int &length, const unsigned max_length, bool &baudrate_changed, unsigned &baudrate) = 0; + virtual void configure(const int &fd, bool &baudrate_changed, unsigned &baudrate) = 0; virtual void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated) = 0; }; diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index a823271758..8e2396564d 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -68,11 +68,8 @@ UBX::reset() } void -UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &baudrate_changed, unsigned &baudrate) +UBX::configure(const int &fd, bool &baudrate_changed, unsigned &baudrate) { - /* make sure the buffer, where the message is written to, is long enough */ - assert(sizeof(type_gps_bin_cfg_prt_packet_t)+2 <= max_length); - /* Only send a new config message when we got the ACK of the last one, * otherwise we might not configure all the messages because the ACK comes from an older/previos CFD command * reason being that the ACK only includes CFG-MSG but not to which NAV MSG it belongs. @@ -105,16 +102,7 @@ UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &ba cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; - /* Calculate the checksum now */ - addChecksumToMessage((uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); - - /* Start with the two sync bytes */ - buffer[0] = UBX_SYNC1; - buffer[1] = UBX_SYNC2; - /* Copy it to the buffer that will be written back in the main gps driver */ - memcpy(&(buffer[2]), &cfg_prt_packet, sizeof(cfg_prt_packet)); - /* Set the length of the packet (plus the 2 sync bytes) */ - length = sizeof(cfg_prt_packet)+2; + sendConfigPacket(fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); } else if (_config_state == UBX_CONFIG_STATE_PRT_NEW_BAUDRATE) { @@ -131,12 +119,7 @@ UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &ba cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; - addChecksumToMessage((uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); - - buffer[0] = UBX_SYNC1; - buffer[1] = UBX_SYNC2; - memcpy(&(buffer[2]), &cfg_prt_packet, sizeof(cfg_prt_packet)); - length = sizeof(cfg_prt_packet)+2; + sendConfigPacket(fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); /* If the new baudrate will be different from the current one, we should report that back to the driver */ if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) { @@ -160,12 +143,7 @@ UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &ba cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE; cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF; - addChecksumToMessage((uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet)); - - buffer[0] = UBX_SYNC1; - buffer[1] = UBX_SYNC2; - memcpy(&(buffer[2]), &cfg_rate_packet, sizeof(cfg_rate_packet)); - length = sizeof(cfg_rate_packet)+2; + sendConfigPacket(fd, (uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet)); } else if (_config_state == UBX_CONFIG_STATE_NAV5) { /* send a NAV5 message to set the options for the internal filter */ @@ -179,12 +157,7 @@ UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &ba cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL; cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE; - addChecksumToMessage((uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet)); - - buffer[0] = UBX_SYNC1; - buffer[1] = UBX_SYNC2; - memcpy(&(buffer[2]), &cfg_nav5_packet, sizeof(cfg_nav5_packet)); - length = sizeof(cfg_nav5_packet)+2; + sendConfigPacket(fd, (uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet)); } else { /* Catch the remaining config states here, they all need the same packet type */ @@ -233,12 +206,7 @@ UBX::configure(uint8_t *buffer, int &length, const unsigned max_length, bool &ba break; } - addChecksumToMessage((uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); - - buffer[0] = UBX_SYNC1; - buffer[1] = UBX_SYNC2; - memcpy(&(buffer[2]), &cfg_msg_packet, sizeof(cfg_msg_packet)); - length = sizeof(cfg_msg_packet)+2; + sendConfigPacket(fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); } } } @@ -779,3 +747,21 @@ UBX::addChecksumToMessage(uint8_t* message, const unsigned length) message[length-2] = ck_a; message[length-1] = ck_b; } + +void +UBX::sendConfigPacket(const int &fd, uint8_t *packet, const unsigned length) +{ + ssize_t ret = 0; + + /* Calculate the checksum now */ + addChecksumToMessage(packet, length); + + const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2}; + + /* Start with the two sync bytes */ + ret += write(fd, sync_bytes, sizeof(sync_bytes)); + ret += write(fd, packet, length); + + if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning? + warnx("ubx: config write fail"); +} diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index a23bb55025..c420e83b9e 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -40,7 +40,6 @@ #include "gps_helper.h" - #define UBX_SYNC1 0xB5 #define UBX_SYNC2 0x62 @@ -341,7 +340,7 @@ public: UBX(); ~UBX(); void reset(void); - void configure(uint8_t *buffer, int &length, const unsigned max_length, bool &baudrate_changed, unsigned &baudrate); + void configure(const int &fd, bool &baudrate_changed, unsigned &baudrate); void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated); private: @@ -358,7 +357,13 @@ private: /** * Add the two checksum bytes to an outgoing message */ - void addChecksumToMessage(uint8_t*, const unsigned); + void addChecksumToMessage(uint8_t* message, const unsigned length); + + /** + * Helper to send a config packet + */ + void sendConfigPacket(const int &fd, uint8_t *packet, const unsigned length); + ubx_config_state_t _config_state; bool _waiting_for_ack; ubx_decode_state_t _decode_state; From 0d54661ce90dfe2440daea2639a9853520d8366c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 6 Feb 2013 20:04:49 -0800 Subject: [PATCH 16/20] Added MTK 1.6, works after some seconds, work in progress --- apps/drivers/gps/gps.cpp | 43 +++++---- apps/drivers/gps/mtk.cpp | 184 +++++++++++++++++++++++++++++++++++++++ apps/drivers/gps/mtk.h | 108 +++++++++++++++++++++++ 3 files changed, 320 insertions(+), 15 deletions(-) create mode 100644 apps/drivers/gps/mtk.cpp create mode 100644 apps/drivers/gps/mtk.h diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 3e1aca810c..c749e8b7f1 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -77,7 +77,7 @@ #define SEND_BUFFER_LENGTH 100 #define TIMEOUT 1000000 //1s -#define NUMBER_OF_BAUDRATES 4 +#define NUMBER_OF_TRIES 5 #define CONFIG_TIMEOUT 2000000 /* oddly, ERROR is not defined for c++ */ @@ -113,7 +113,8 @@ private: int _serial_fd; ///< serial interface to GPS unsigned _baudrate; ///< current baudrate char _port[20]; ///< device / serial port path - const unsigned _baudrates_to_try[NUMBER_OF_BAUDRATES]; ///< try different baudrates that GPS could be set to + const unsigned _baudrates_to_try[NUMBER_OF_TRIES]; ///< try different baudrates that GPS could be set to + const gps_driver_mode_t _modes_to_try[NUMBER_OF_TRIES]; ///< try different modes volatile int _task; //< worker task bool _config_needed; ///< flag to signal that configuration of GPS is needed bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed @@ -170,11 +171,11 @@ GPS *g_dev; GPS::GPS(const char* uart_path) : CDev("gps", GPS_DEVICE_PATH), _task_should_exit(false), - _baudrates_to_try({9600, 38400, 57600, 115200}), + _baudrates_to_try({9600, 38400, 57600, 115200, 38400}), + _modes_to_try({GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_MTK}), _config_needed(true), _baudrate_changed(false), - _mode_changed(true), - _mode(GPS_DRIVER_MODE_UBX), + _mode_changed(false), _Helper(nullptr), _report_pub(-1), _rate(0.0f) @@ -295,8 +296,10 @@ GPS::task_main() /* lock against the ioctl handler */ lock(); - unsigned baud_i = 0; - _baudrate = _baudrates_to_try[baud_i]; + unsigned try_i = 0; + _baudrate = _baudrates_to_try[try_i]; + _mode = _modes_to_try[try_i]; + _mode_changed = true; set_baudrate(_baudrate); uint64_t time_before_configuration = hrt_absolute_time(); @@ -310,6 +313,23 @@ GPS::task_main() /* loop handling received serial bytes and also configuring in between */ while (!_task_should_exit) { + /* If a configuration does not finish in the config timeout, change the baudrate */ + if (_config_needed && time_before_configuration + CONFIG_TIMEOUT < hrt_absolute_time()) { + /* loop through possible modes/baudrates */ + try_i = (try_i + 1) % NUMBER_OF_TRIES; + _baudrate = _baudrates_to_try[try_i]; + set_baudrate(_baudrate); + if (_mode != _modes_to_try[try_i]) { + _mode_changed = true; + } + _mode = _modes_to_try[try_i]; + + if (_Helper != nullptr) { + _Helper->reset(); + } + time_before_configuration = hrt_absolute_time(); + } + if (_mode_changed) { if (_Helper != nullptr) { delete(_Helper); @@ -333,14 +353,7 @@ GPS::task_main() _mode_changed = false; } - /* If a configuration does not finish in the config timeout, change the baudrate */ - if (_config_needed && time_before_configuration + CONFIG_TIMEOUT < hrt_absolute_time()) { - baud_i = (baud_i+1)%NUMBER_OF_BAUDRATES; - _baudrate = _baudrates_to_try[baud_i]; - set_baudrate(_baudrate); - _Helper->reset(); - time_before_configuration = hrt_absolute_time(); - } + /* during configuration, the timeout should be small, so that we can send config messages in between parsing, * but during normal operation, it should never timeout because updates should arrive with 5Hz */ diff --git a/apps/drivers/gps/mtk.cpp b/apps/drivers/gps/mtk.cpp new file mode 100644 index 0000000000..555fb7a515 --- /dev/null +++ b/apps/drivers/gps/mtk.cpp @@ -0,0 +1,184 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Author: Thomas Gubler + * Julian Oes + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* @file mkt.cpp */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "mtk.h" + + +MTK::MTK() +{ + decodeInit(); +} + +MTK::~MTK() +{ +} + +void +MTK::reset() +{ + +} + +void +MTK::configure(const int &fd, bool &baudrate_changed, unsigned &baudrate) +{ + if (strlen(MTK_OUTPUT_5HZ) != write(fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) + warnx("mtk: config write failed"); + usleep(10000); + + if (strlen(MTK_SET_BINARY) != write(fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) + warnx("mtk: config write failed"); + usleep(10000); + + if (strlen(SBAS_ON) != write(fd, SBAS_ON, strlen(SBAS_ON))) + warnx("mtk: config write failed"); + usleep(10000); + + if (strlen(WAAS_ON) != write(fd, WAAS_ON, strlen(WAAS_ON))) + warnx("mtk: config write failed"); + usleep(10000); + + if (strlen(MTK_NAVTHRES_OFF) != write(fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) + warnx("mtk: config write failed"); + + return; +} + +void +MTK::decodeInit(void) +{ + _rx_ck_a = 0; + _rx_ck_b = 0; + _rx_count = 0; + _decode_state = MTK_DECODE_UNINIT; +} + +void +MTK::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_needed, bool &pos_updated) +{ + if (_decode_state == MTK_DECODE_UNINIT) { + + if (b == 0xd0) { + _decode_state = MTK_DECODE_GOT_CK_A; + config_needed = false; + } + + } else if (_decode_state == MTK_DECODE_GOT_CK_A) { + if (b == 0xdd) { + _decode_state = MTK_DECODE_GOT_CK_B; + + } else { + // Second start symbol was wrong, reset state machine + decodeInit(); + } + + } else if (_decode_state == MTK_DECODE_GOT_CK_B) { + // Add to checksum + if (_rx_count < 33) + addByteToChecksum(b); + + // Fill packet buffer + _rx_buffer[_rx_count] = b; + _rx_count++; + + /* Packet size minus checksum */ + if (_rx_count >= 35) { + type_gps_mtk_packet *packet = (type_gps_mtk_packet *) _rx_buffer;; + + /* Check if checksum is valid */ + if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { + gps_position->lat = packet->latitude * 10; // from degrees*1e6 to degrees*1e7 + gps_position->lon = packet->longitude * 10; // from degrees*1e6 to degrees*1e7 + gps_position->alt = (int32_t)(packet->msl_altitude * 10); // from cm to mm + gps_position->fix_type = packet->fix_type; + gps_position->eph_m = packet->hdop; + gps_position->epv_m = 0.0; //unknown in mtk custom mode + gps_position->vel_m_s = ((float)packet->ground_speed)*1e-2f; // from cm/s to m/s + gps_position->cog_rad = ((float)packet->heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad + gps_position->satellites_visible = packet->satellites; + + /* convert time and date information to unix timestamp */ + struct tm timeinfo; //TODO: test this conversion + uint32_t timeinfo_conversion_temp; + + timeinfo.tm_mday = packet->date * 1e-4; + timeinfo_conversion_temp = packet->date - timeinfo.tm_mday * 1e4; + timeinfo.tm_mon = timeinfo_conversion_temp * 1e-2 - 1; + timeinfo.tm_year = (timeinfo_conversion_temp - (timeinfo.tm_mon + 1) * 1e2) + 100; + + timeinfo.tm_hour = packet->utc_time * 1e-7; + timeinfo_conversion_temp = packet->utc_time - timeinfo.tm_hour * 1e7; + timeinfo.tm_min = timeinfo_conversion_temp * 1e-5; + timeinfo_conversion_temp -= timeinfo.tm_min * 1e5; + timeinfo.tm_sec = timeinfo_conversion_temp * 1e-3; + timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3; + time_t epoch = mktime(&timeinfo); + + gps_position->time_gps_usec = epoch * 1e6; //TODO: test this + gps_position->time_gps_usec += timeinfo_conversion_temp * 1e3; + gps_position->timestamp_position = gps_position->timestamp_time = hrt_absolute_time(); + + pos_updated = true; + + + } else { + warnx("mtk Checksum invalid, 0x%x, 0x%x instead of 0x%x, 0x%x", _rx_ck_a, packet->ck_a, _rx_ck_b, packet->ck_b); + } + + // Reset state machine to decode next packet + decodeInit(); + } + } + return; +} + +void +MTK::addByteToChecksum(uint8_t b) +{ + _rx_ck_a = _rx_ck_a + b; + _rx_ck_b = _rx_ck_b + _rx_ck_a; +} diff --git a/apps/drivers/gps/mtk.h b/apps/drivers/gps/mtk.h new file mode 100644 index 0000000000..8929eb041c --- /dev/null +++ b/apps/drivers/gps/mtk.h @@ -0,0 +1,108 @@ +/**************************************************************************** + * + * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. + * Author: Thomas Gubler + * Julian Oes + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* @file mtk.h */ + +#ifndef MTK_H_ +#define MTK_H_ + +#include "gps_helper.h" + +#define MTK_SYNC1 0xd0 +#define MTK_SYNC2 0xdd + +#define MTK_OUTPUT_5HZ "$PMTK220,200*2C\r\n" +#define MTK_SET_BINARY "$PGCMD,16,0,0,0,0,0*6A\r\n" +#define SBAS_ON "$PMTK313,1*2E\r\n" +#define WAAS_ON "$PMTK301,2*2E\r\n" +#define MTK_NAVTHRES_OFF "$PMTK397,0*23\r\n" + +typedef enum { + MTK_DECODE_UNINIT = 0, + MTK_DECODE_GOT_CK_A = 1, + MTK_DECODE_GOT_CK_B = 2 +} mtk_decode_state_t; + +/** the structures of the binary packets */ +#pragma pack(push, 1) + +typedef struct { + uint8_t payload; ///< Number of payload bytes + int32_t latitude; ///< Latitude in degrees * 10^7 + int32_t longitude; ///< Longitude in degrees * 10^7 + uint32_t msl_altitude; ///< MSL altitude in meters * 10^2 + uint32_t ground_speed; ///< FIXME SPEC UNCLEAR + int32_t heading; + uint8_t satellites; + uint8_t fix_type; + uint32_t date; + uint32_t utc_time; + uint16_t hdop; + uint8_t ck_a; + uint8_t ck_b; +} type_gps_mtk_packet; + +#pragma pack(pop) + +#define MTK_RECV_BUFFER_SIZE 40 + +class MTK : public GPS_Helper +{ +public: + MTK(); + ~MTK(); + void reset(void); + void configure(const int &fd, bool &baudrate_changed, unsigned &baudrate); + void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated); + +private: + /** + * Reset the parse state machine for a fresh start + */ + void decodeInit(void); + + /** + * While parsing add every byte (except the sync bytes) to the checksum + */ + void addByteToChecksum(uint8_t); + + mtk_decode_state_t _decode_state; + uint8_t _rx_buffer[MTK_RECV_BUFFER_SIZE]; + unsigned _rx_count; + uint8_t _rx_ck_a; + uint8_t _rx_ck_b; +}; + +#endif /* MTK_H_ */ From b620136af4f8de913fd12872a91a80f62861dc4c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 6 Feb 2013 22:58:52 -0800 Subject: [PATCH 17/20] Added support for MTK revision 19, working condition but configuration of MTK is very slow and needs improvement --- apps/drivers/gps/mtk.cpp | 25 +++++++++++++++++++------ apps/drivers/gps/mtk.h | 4 +++- 2 files changed, 22 insertions(+), 7 deletions(-) diff --git a/apps/drivers/gps/mtk.cpp b/apps/drivers/gps/mtk.cpp index 555fb7a515..bed388c49b 100644 --- a/apps/drivers/gps/mtk.cpp +++ b/apps/drivers/gps/mtk.cpp @@ -48,7 +48,8 @@ #include "mtk.h" -MTK::MTK() +MTK::MTK() : +_mtk_revision(0) { decodeInit(); } @@ -102,13 +103,18 @@ MTK::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ { if (_decode_state == MTK_DECODE_UNINIT) { - if (b == 0xd0) { + if (b == MTK_SYNC1_V16) { _decode_state = MTK_DECODE_GOT_CK_A; config_needed = false; + _mtk_revision = 16; + } else if (b == MTK_SYNC1_V19) { + _decode_state = MTK_DECODE_GOT_CK_A; + config_needed = false; + _mtk_revision = 19; } } else if (_decode_state == MTK_DECODE_GOT_CK_A) { - if (b == 0xdd) { + if (b == MTK_SYNC2) { _decode_state = MTK_DECODE_GOT_CK_B; } else { @@ -131,11 +137,18 @@ MTK::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ /* Check if checksum is valid */ if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - gps_position->lat = packet->latitude * 10; // from degrees*1e6 to degrees*1e7 - gps_position->lon = packet->longitude * 10; // from degrees*1e6 to degrees*1e7 + if (_mtk_revision == 16) { + gps_position->lat = packet->latitude * 10; // from degrees*1e6 to degrees*1e7 + gps_position->lon = packet->longitude * 10; // from degrees*1e6 to degrees*1e7 + } else if (_mtk_revision == 19) { + gps_position->lat = packet->latitude; // both degrees*1e7 + gps_position->lon = packet->longitude; // both degrees*1e7 + } else { + warnx("mtk: unknown revision"); + } gps_position->alt = (int32_t)(packet->msl_altitude * 10); // from cm to mm gps_position->fix_type = packet->fix_type; - gps_position->eph_m = packet->hdop; + gps_position->eph_m = packet->hdop; // XXX: Check this because eph_m is in m and hdop is without unit gps_position->epv_m = 0.0; //unknown in mtk custom mode gps_position->vel_m_s = ((float)packet->ground_speed)*1e-2f; // from cm/s to m/s gps_position->cog_rad = ((float)packet->heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad diff --git a/apps/drivers/gps/mtk.h b/apps/drivers/gps/mtk.h index 8929eb041c..7a4b4f197c 100644 --- a/apps/drivers/gps/mtk.h +++ b/apps/drivers/gps/mtk.h @@ -40,7 +40,8 @@ #include "gps_helper.h" -#define MTK_SYNC1 0xd0 +#define MTK_SYNC1_V16 0xd0 +#define MTK_SYNC1_V19 0xd1 #define MTK_SYNC2 0xdd #define MTK_OUTPUT_5HZ "$PMTK220,200*2C\r\n" @@ -99,6 +100,7 @@ private: void addByteToChecksum(uint8_t); mtk_decode_state_t _decode_state; + uint8_t _mtk_revision; uint8_t _rx_buffer[MTK_RECV_BUFFER_SIZE]; unsigned _rx_count; uint8_t _rx_ck_a; From d36eb8a3fcce358409a7205bbd75576a447ac7b4 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 6 Feb 2013 23:25:09 -0800 Subject: [PATCH 18/20] Sped up MTK configuration but the detection time can still be improved: timeouts/usleeps --- apps/drivers/gps/mtk.cpp | 34 ++++++++++++++++++++-------------- apps/drivers/gps/mtk.h | 3 ++- 2 files changed, 22 insertions(+), 15 deletions(-) diff --git a/apps/drivers/gps/mtk.cpp b/apps/drivers/gps/mtk.cpp index bed388c49b..026b0660b5 100644 --- a/apps/drivers/gps/mtk.cpp +++ b/apps/drivers/gps/mtk.cpp @@ -49,6 +49,7 @@ MTK::MTK() : +_config_sent(false), _mtk_revision(0) { decodeInit(); @@ -67,24 +68,29 @@ MTK::reset() void MTK::configure(const int &fd, bool &baudrate_changed, unsigned &baudrate) { - if (strlen(MTK_OUTPUT_5HZ) != write(fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) - warnx("mtk: config write failed"); - usleep(10000); + if (_config_sent == false) { - if (strlen(MTK_SET_BINARY) != write(fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) - warnx("mtk: config write failed"); - usleep(10000); + if (strlen(MTK_OUTPUT_5HZ) != write(fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) + warnx("mtk: config write failed"); + usleep(10000); - if (strlen(SBAS_ON) != write(fd, SBAS_ON, strlen(SBAS_ON))) - warnx("mtk: config write failed"); - usleep(10000); + if (strlen(MTK_SET_BINARY) != write(fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) + warnx("mtk: config write failed"); + usleep(10000); - if (strlen(WAAS_ON) != write(fd, WAAS_ON, strlen(WAAS_ON))) - warnx("mtk: config write failed"); - usleep(10000); + if (strlen(SBAS_ON) != write(fd, SBAS_ON, strlen(SBAS_ON))) + warnx("mtk: config write failed"); + usleep(10000); - if (strlen(MTK_NAVTHRES_OFF) != write(fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) - warnx("mtk: config write failed"); + if (strlen(WAAS_ON) != write(fd, WAAS_ON, strlen(WAAS_ON))) + warnx("mtk: config write failed"); + usleep(10000); + + if (strlen(MTK_NAVTHRES_OFF) != write(fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) + warnx("mtk: config write failed"); + + _config_sent = true; + } return; } diff --git a/apps/drivers/gps/mtk.h b/apps/drivers/gps/mtk.h index 7a4b4f197c..e436371958 100644 --- a/apps/drivers/gps/mtk.h +++ b/apps/drivers/gps/mtk.h @@ -99,7 +99,8 @@ private: */ void addByteToChecksum(uint8_t); - mtk_decode_state_t _decode_state; + mtk_decode_state_t _decode_state; + bool _config_sent; uint8_t _mtk_revision; uint8_t _rx_buffer[MTK_RECV_BUFFER_SIZE]; unsigned _rx_count; From a88b9f4eefe8315cb692779dd300400d8052eb44 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 7 Feb 2013 14:48:00 -0800 Subject: [PATCH 19/20] Restructered the parsing/configuring, MTK working --- apps/drivers/gps/gps.cpp | 239 ++++++------------------------- apps/drivers/gps/gps_helper.cpp | 90 ++++++++++++ apps/drivers/gps/gps_helper.h | 11 +- apps/drivers/gps/mtk.cpp | 240 ++++++++++++++++++++------------ apps/drivers/gps/mtk.h | 35 +++-- 5 files changed, 313 insertions(+), 302 deletions(-) create mode 100644 apps/drivers/gps/gps_helper.cpp diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index c749e8b7f1..76b5f45336 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -53,7 +53,6 @@ #include #include #include -#include #include #include @@ -71,7 +70,7 @@ #include -#include "ubx.h" +//#include "ubx.h" #include "mtk.h" #define SEND_BUFFER_LENGTH 100 @@ -113,10 +112,8 @@ private: int _serial_fd; ///< serial interface to GPS unsigned _baudrate; ///< current baudrate char _port[20]; ///< device / serial port path - const unsigned _baudrates_to_try[NUMBER_OF_TRIES]; ///< try different baudrates that GPS could be set to - const gps_driver_mode_t _modes_to_try[NUMBER_OF_TRIES]; ///< try different modes volatile int _task; //< worker task - bool _config_needed; ///< flag to signal that configuration of GPS is needed + bool _healthy; ///< flag to signal if the GPS is ok bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed bool _mode_changed; ///< flag that the GPS mode has changed gps_driver_mode_t _mode; ///< current mode @@ -171,11 +168,9 @@ GPS *g_dev; GPS::GPS(const char* uart_path) : CDev("gps", GPS_DEVICE_PATH), _task_should_exit(false), - _baudrates_to_try({9600, 38400, 57600, 115200, 38400}), - _modes_to_try({GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_MTK}), - _config_needed(true), - _baudrate_changed(false), + _healthy(false), _mode_changed(false), + _mode(GPS_DRIVER_MODE_MTK), _Helper(nullptr), _report_pub(-1), _rate(0.0f) @@ -250,20 +245,6 @@ GPS::ioctl(struct file *filp, int cmd, unsigned long arg) return ret; } -void -GPS::config() -{ - _Helper->configure(_serial_fd, _baudrate_changed, _baudrate); - - /* Sometimes the baudrate needs to be changed, for instance UBX with factory settings are changed - * from 9600 to 38400 - */ - if (_baudrate_changed) { - set_baudrate(_baudrate); - _baudrate_changed = false; - } -} - void GPS::task_main_trampoline(void *arg) { @@ -276,10 +257,7 @@ GPS::task_main() log("starting"); /* open the serial port */ - _serial_fd = ::open(_port, O_RDWR); //TODO make the device dynamic depending on startup parameters - - /* buffer to read from the serial port */ - uint8_t buf[32]; + _serial_fd = ::open(_port, O_RDWR); if (_serial_fd < 0) { log("failed to open serial port: %s err: %d", _port, errno); @@ -288,151 +266,65 @@ GPS::task_main() _exit(1); } - /* poll descriptor */ - pollfd fds[1]; - fds[0].fd = _serial_fd; - fds[0].events = POLLIN; - - /* lock against the ioctl handler */ - lock(); - - unsigned try_i = 0; - _baudrate = _baudrates_to_try[try_i]; - _mode = _modes_to_try[try_i]; - _mode_changed = true; - set_baudrate(_baudrate); - - uint64_t time_before_configuration = hrt_absolute_time(); - uint64_t last_rate_measurement = hrt_absolute_time(); unsigned last_rate_count = 0; - bool pos_updated; - bool config_needed_res; - /* loop handling received serial bytes and also configuring in between */ while (!_task_should_exit) { - /* If a configuration does not finish in the config timeout, change the baudrate */ - if (_config_needed && time_before_configuration + CONFIG_TIMEOUT < hrt_absolute_time()) { - /* loop through possible modes/baudrates */ - try_i = (try_i + 1) % NUMBER_OF_TRIES; - _baudrate = _baudrates_to_try[try_i]; - set_baudrate(_baudrate); - if (_mode != _modes_to_try[try_i]) { - _mode_changed = true; - } - _mode = _modes_to_try[try_i]; - - if (_Helper != nullptr) { - _Helper->reset(); - } - time_before_configuration = hrt_absolute_time(); + if (_Helper != nullptr) { + delete(_Helper); + /* set to zero to ensure parser is not used while not instantiated */ + _Helper = nullptr; } - if (_mode_changed) { - if (_Helper != nullptr) { - delete(_Helper); - /* set to zero to ensure parser is not used while not instantiated */ - _Helper = nullptr; - } - - switch (_mode) { - case GPS_DRIVER_MODE_UBX: - _Helper = new UBX(); - break; + switch (_mode) { +// case GPS_DRIVER_MODE_UBX: +// _Helper = new UBX(); +// break; case GPS_DRIVER_MODE_MTK: + printf("try new mtk\n"); _Helper = new MTK(); break; case GPS_DRIVER_MODE_NMEA: - //_Helper = new NMEA(); + //_Helper = new NMEA(); //TODO: add NMEA break; default: break; - } - _mode_changed = false; } - - - - /* during configuration, the timeout should be small, so that we can send config messages in between parsing, - * but during normal operation, it should never timeout because updates should arrive with 5Hz */ - int poll_timeout; - if (_config_needed) { - poll_timeout = 50; - } else { - poll_timeout = 400; - } - /* sleep waiting for data, but no more than the poll timeout */ + // XXX unlock/lock makes sense? unlock(); - int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), poll_timeout); - lock(); + if (_Helper->configure(_serial_fd, _baudrate) == 0) { + while (_Helper->receive(_serial_fd, _report) > 0 && !_task_should_exit) { + /* opportunistic publishing - else invalid data would end up on the bus */ + if (_report_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + } else { + _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } - /* this would be bad... */ - if (ret < 0) { - log("poll error %d", errno); - } else if (ret == 0) { - /* no response from the GPS */ - if (_config_needed == false) { - _config_needed = true; - warnx("GPS module timeout"); - _Helper->reset(); - } - config(); - } else if (ret > 0) { - /* if we have new data from GPS, go handle it */ - if (fds[0].revents & POLLIN) { - int count; + last_rate_count++; - /* - * We are here because poll says there is some data, so this - * won't block even on a blocking device. If more bytes are - * available, we'll go back to poll() again... - */ - count = ::read(_serial_fd, buf, sizeof(buf)); + /* measure update rate every 5 seconds */ + if (hrt_absolute_time() - last_rate_measurement > 5000000) { + _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f); + last_rate_measurement = hrt_absolute_time(); + last_rate_count = 0; + } - /* pass received bytes to the packet decoder */ - int j; - for (j = 0; j < count; j++) { - pos_updated = false; - config_needed_res = _config_needed; - _Helper->parse(buf[j], &_report, config_needed_res, pos_updated); - - if (pos_updated) { - /* opportunistic publishing - else invalid data would end up on the bus */ - if (_report_pub > 0) { - orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); - } else { - _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); - } - last_rate_count++; - - /* measure update rate every 5 seconds */ - if (hrt_absolute_time() - last_rate_measurement > 5000000) { - _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f); - last_rate_measurement = hrt_absolute_time(); - last_rate_count = 0; - } - - } - if (config_needed_res == true && _config_needed == false) { - /* the parser told us that an error happened and reconfiguration is needed */ - _config_needed = true; - warnx("GPS module lost"); - _Helper->reset(); - config(); - } else if (config_needed_res == true && _config_needed == true) { - /* we are still configuring */ - config(); - } else if (config_needed_res == false && _config_needed == true) { - /* the parser is happy, stop configuring */ - warnx("GPS module found"); - _config_needed = false; - } + if (!_healthy) { + warnx("module found"); + _healthy = true; } } + if (_healthy) { + warnx("module lost"); + _healthy = false; + _rate = 0.0f; + } } + lock(); } debug("exiting"); @@ -443,59 +335,12 @@ GPS::task_main() _exit(0); } -int -GPS::set_baudrate(unsigned baud) -{ - /* process baud rate */ - int speed; - switch (baud) { - case 9600: speed = B9600; break; - - case 19200: speed = B19200; break; - - case 38400: speed = B38400; break; - - case 57600: speed = B57600; break; - - case 115200: speed = B115200; break; - - default: - warnx("ERROR: Unsupported baudrate: %d\n", baud); - return -EINVAL; - } - struct termios uart_config; - int termios_state; - - /* fill the struct for the new configuration */ - tcgetattr(_serial_fd, &uart_config); - - /* clear ONLCR flag (which appends a CR for every LF) */ - uart_config.c_oflag &= ~ONLCR; - /* no parity, one stop bit */ - uart_config.c_cflag &= ~(CSTOPB | PARENB); - - /* set baud rate */ - if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { - warnx("ERROR setting config: %d (cfsetispeed)\n", termios_state); - return -1; - } - if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { - warnx("ERROR setting config: %d (cfsetospeed)\n", termios_state); - return -1; - } - if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) { - warnx("ERROR setting baudrate (tcsetattr)\n"); - return -1; - } - /* XXX if resetting the parser here, ensure it does exist (check for null pointer) */ - return 0; -} void GPS::cmd_reset() { - _config_needed = true; + //XXX add reset? } void @@ -514,7 +359,7 @@ GPS::print_info() default: break; } - warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_config_needed) ? "NOT OK" : "OK"); + warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK"); if (_report.timestamp_position != 0) { warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type, (double)((float)(hrt_absolute_time() - _report.timestamp_position) / 1000000.0f)); diff --git a/apps/drivers/gps/gps_helper.cpp b/apps/drivers/gps/gps_helper.cpp new file mode 100644 index 0000000000..2caa82af15 --- /dev/null +++ b/apps/drivers/gps/gps_helper.cpp @@ -0,0 +1,90 @@ +/**************************************************************************** + * + * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. + * Author: Thomas Gubler + * Julian Oes + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include +#include "gps_helper.h" + +/* @file gps_helper.cpp */ + +int +GPS_Helper::set_baudrate(const int &fd, unsigned baud) +{ + /* process baud rate */ + int speed; + + switch (baud) { + case 9600: speed = B9600; break; + + case 19200: speed = B19200; break; + + case 38400: speed = B38400; break; + + case 57600: speed = B57600; break; + + case 115200: speed = B115200; break; + + default: + warnx("ERROR: Unsupported baudrate: %d\n", baud); + return -EINVAL; + } + struct termios uart_config; + int termios_state; + + /* fill the struct for the new configuration */ + tcgetattr(fd, &uart_config); + + /* clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + /* no parity, one stop bit */ + uart_config.c_cflag &= ~(CSTOPB | PARENB); + + /* set baud rate */ + if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { + warnx("ERROR setting config: %d (cfsetispeed)\n", termios_state); + return -1; + } + if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { + warnx("ERROR setting config: %d (cfsetospeed)\n", termios_state); + return -1; + } + if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) { + warnx("ERROR setting baudrate (tcsetattr)\n"); + return -1; + } + /* XXX if resetting the parser here, ensure it does exist (check for null pointer) */ + return 0; +} diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h index 576692c2a4..537ca819ce 100644 --- a/apps/drivers/gps/gps_helper.h +++ b/apps/drivers/gps/gps_helper.h @@ -33,17 +33,20 @@ * ****************************************************************************/ -/* @file U-Blox protocol definitions */ +/* @file gps_helper.h */ #ifndef GPS_HELPER_H #define GPS_HELPER_H +#include +#include + class GPS_Helper { public: - virtual void reset(void) = 0; - virtual void configure(const int &fd, bool &baudrate_changed, unsigned &baudrate) = 0; - virtual void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated) = 0; + virtual int configure(const int &fd, unsigned &baud) = 0; + virtual int receive(const int &fd, struct vehicle_gps_position_s &gps_position) = 0; + int set_baudrate(const int &fd, unsigned baud); }; #endif /* GPS_HELPER_H */ diff --git a/apps/drivers/gps/mtk.cpp b/apps/drivers/gps/mtk.cpp index 026b0660b5..4ccbbfbe4a 100644 --- a/apps/drivers/gps/mtk.cpp +++ b/apps/drivers/gps/mtk.cpp @@ -37,85 +37,143 @@ #include #include +#include #include #include #include #include -#include -#include #include #include "mtk.h" MTK::MTK() : -_config_sent(false), _mtk_revision(0) { - decodeInit(); + decode_init(); } MTK::~MTK() { } -void -MTK::reset() +int +MTK::configure(const int &fd, unsigned &baudrate) { + /* set baudrate first */ + if (GPS_Helper::set_baudrate(fd, MTK_BAUDRATE) != 0) + return -1; -} + baudrate = MTK_BAUDRATE; -void -MTK::configure(const int &fd, bool &baudrate_changed, unsigned &baudrate) -{ - if (_config_sent == false) { + /* Write config messages, don't wait for an answer */ + if (strlen(MTK_OUTPUT_5HZ) != write(fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) { + warnx("mtk: config write failed"); + return -1; + } + usleep(10000); - if (strlen(MTK_OUTPUT_5HZ) != write(fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) - warnx("mtk: config write failed"); - usleep(10000); + if (strlen(MTK_SET_BINARY) != write(fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) { + warnx("mtk: config write failed"); + return -1; + } + usleep(10000); - if (strlen(MTK_SET_BINARY) != write(fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) - warnx("mtk: config write failed"); - usleep(10000); + if (strlen(SBAS_ON) != write(fd, SBAS_ON, strlen(SBAS_ON))) { + warnx("mtk: config write failed"); + return -1; + } + usleep(10000); - if (strlen(SBAS_ON) != write(fd, SBAS_ON, strlen(SBAS_ON))) - warnx("mtk: config write failed"); - usleep(10000); + if (strlen(WAAS_ON) != write(fd, WAAS_ON, strlen(WAAS_ON))) { + warnx("mtk: config write failed"); + return -1; + } + usleep(10000); - if (strlen(WAAS_ON) != write(fd, WAAS_ON, strlen(WAAS_ON))) - warnx("mtk: config write failed"); - usleep(10000); - - if (strlen(MTK_NAVTHRES_OFF) != write(fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) - warnx("mtk: config write failed"); - - _config_sent = true; + if (strlen(MTK_NAVTHRES_OFF) != write(fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) { + warnx("mtk: config write failed"); + return -1; } - return; + return 0; +} + +int +MTK::receive(const int &fd, struct vehicle_gps_position_s &gps_position) +{ + /* poll descriptor */ + pollfd fds[1]; + fds[0].fd = fd; + fds[0].events = POLLIN; + + uint8_t buf[32]; + gps_mtk_packet_t packet; + + int j = 0; + ssize_t count = 0; + + while (true) { + + /* first read whatever is left */ + if (j < count) { + /* pass received bytes to the packet decoder */ + while (j < count) { + if (parse_char(buf[j], packet) > 0) { + handle_message(packet, gps_position); + return 1; + } + j++; + } + /* everything is read */ + j = count = 0; + } + + /* then poll for new data */ + int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), MTK_TIMEOUT_5HZ); + + if (ret < 0) { + /* something went wrong when polling */ + return -1; + + } else if (ret == 0) { + /* Timeout */ + return -1; + + } else if (ret > 0) { + /* if we have new data from GPS, go handle it */ + if (fds[0].revents & POLLIN) { + /* + * We are here because poll says there is some data, so this + * won't block even on a blocking device. If more bytes are + * available, we'll go back to poll() again... + */ + count = ::read(fd, buf, sizeof(buf)); + } + } + } } void -MTK::decodeInit(void) +MTK::decode_init(void) { _rx_ck_a = 0; _rx_ck_b = 0; _rx_count = 0; _decode_state = MTK_DECODE_UNINIT; } - -void -MTK::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_needed, bool &pos_updated) +int +MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet) { + int ret = 0; + if (_decode_state == MTK_DECODE_UNINIT) { if (b == MTK_SYNC1_V16) { _decode_state = MTK_DECODE_GOT_CK_A; - config_needed = false; _mtk_revision = 16; } else if (b == MTK_SYNC1_V19) { _decode_state = MTK_DECODE_GOT_CK_A; - config_needed = false; _mtk_revision = 19; } @@ -125,78 +183,82 @@ MTK::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ } else { // Second start symbol was wrong, reset state machine - decodeInit(); + decode_init(); } } else if (_decode_state == MTK_DECODE_GOT_CK_B) { // Add to checksum if (_rx_count < 33) - addByteToChecksum(b); + add_byte_to_checksum(b); // Fill packet buffer - _rx_buffer[_rx_count] = b; + ((uint8_t*)(&packet))[_rx_count] = b; _rx_count++; - /* Packet size minus checksum */ - if (_rx_count >= 35) { - type_gps_mtk_packet *packet = (type_gps_mtk_packet *) _rx_buffer;; - - /* Check if checksum is valid */ - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - if (_mtk_revision == 16) { - gps_position->lat = packet->latitude * 10; // from degrees*1e6 to degrees*1e7 - gps_position->lon = packet->longitude * 10; // from degrees*1e6 to degrees*1e7 - } else if (_mtk_revision == 19) { - gps_position->lat = packet->latitude; // both degrees*1e7 - gps_position->lon = packet->longitude; // both degrees*1e7 - } else { - warnx("mtk: unknown revision"); - } - gps_position->alt = (int32_t)(packet->msl_altitude * 10); // from cm to mm - gps_position->fix_type = packet->fix_type; - gps_position->eph_m = packet->hdop; // XXX: Check this because eph_m is in m and hdop is without unit - gps_position->epv_m = 0.0; //unknown in mtk custom mode - gps_position->vel_m_s = ((float)packet->ground_speed)*1e-2f; // from cm/s to m/s - gps_position->cog_rad = ((float)packet->heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad - gps_position->satellites_visible = packet->satellites; - - /* convert time and date information to unix timestamp */ - struct tm timeinfo; //TODO: test this conversion - uint32_t timeinfo_conversion_temp; - - timeinfo.tm_mday = packet->date * 1e-4; - timeinfo_conversion_temp = packet->date - timeinfo.tm_mday * 1e4; - timeinfo.tm_mon = timeinfo_conversion_temp * 1e-2 - 1; - timeinfo.tm_year = (timeinfo_conversion_temp - (timeinfo.tm_mon + 1) * 1e2) + 100; - - timeinfo.tm_hour = packet->utc_time * 1e-7; - timeinfo_conversion_temp = packet->utc_time - timeinfo.tm_hour * 1e7; - timeinfo.tm_min = timeinfo_conversion_temp * 1e-5; - timeinfo_conversion_temp -= timeinfo.tm_min * 1e5; - timeinfo.tm_sec = timeinfo_conversion_temp * 1e-3; - timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3; - time_t epoch = mktime(&timeinfo); - - gps_position->time_gps_usec = epoch * 1e6; //TODO: test this - gps_position->time_gps_usec += timeinfo_conversion_temp * 1e3; - gps_position->timestamp_position = gps_position->timestamp_time = hrt_absolute_time(); - - pos_updated = true; - - + /* Packet size minus checksum, XXX ? */ + if (_rx_count >= sizeof(packet)) { + /* Compare checksum */ + if (_rx_ck_a == packet.ck_a && _rx_ck_b == packet.ck_b) { + ret = 1; } else { - warnx("mtk Checksum invalid, 0x%x, 0x%x instead of 0x%x, 0x%x", _rx_ck_a, packet->ck_a, _rx_ck_b, packet->ck_b); + warnx("MTK Checksum invalid"); + ret = -1; } - // Reset state machine to decode next packet - decodeInit(); + decode_init(); } } + return ret; +} + +void +MTK::handle_message(gps_mtk_packet_t &packet, struct vehicle_gps_position_s &gps_position) +{ + if (_mtk_revision == 16) { + gps_position.lat = packet.latitude * 10; // from degrees*1e6 to degrees*1e7 + gps_position.lon = packet.longitude * 10; // from degrees*1e6 to degrees*1e7 + } else if (_mtk_revision == 19) { + gps_position.lat = packet.latitude; // both degrees*1e7 + gps_position.lon = packet.longitude; // both degrees*1e7 + } else { + warnx("mtk: unknown revision"); + gps_position.lat = 0; + gps_position.lon = 0; + } + gps_position.alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm + gps_position.fix_type = packet.fix_type; + gps_position.eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit + gps_position.epv_m = 0.0; //unknown in mtk custom mode + gps_position.vel_m_s = ((float)packet.ground_speed)*1e-2f; // from cm/s to m/s + gps_position.cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad + gps_position.satellites_visible = packet.satellites; + + /* convert time and date information to unix timestamp */ + struct tm timeinfo; //TODO: test this conversion + uint32_t timeinfo_conversion_temp; + + timeinfo.tm_mday = packet.date * 1e-4; + timeinfo_conversion_temp = packet.date - timeinfo.tm_mday * 1e4; + timeinfo.tm_mon = timeinfo_conversion_temp * 1e-2 - 1; + timeinfo.tm_year = (timeinfo_conversion_temp - (timeinfo.tm_mon + 1) * 1e2) + 100; + + timeinfo.tm_hour = packet.utc_time * 1e-7; + timeinfo_conversion_temp = packet.utc_time - timeinfo.tm_hour * 1e7; + timeinfo.tm_min = timeinfo_conversion_temp * 1e-5; + timeinfo_conversion_temp -= timeinfo.tm_min * 1e5; + timeinfo.tm_sec = timeinfo_conversion_temp * 1e-3; + timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3; + time_t epoch = mktime(&timeinfo); + + gps_position.time_gps_usec = epoch * 1e6; //TODO: test this + gps_position.time_gps_usec += timeinfo_conversion_temp * 1e3; + gps_position.timestamp_position = gps_position.timestamp_time = hrt_absolute_time(); + return; } void -MTK::addByteToChecksum(uint8_t b) +MTK::add_byte_to_checksum(uint8_t b) { _rx_ck_a = _rx_ck_a + b; _rx_ck_b = _rx_ck_b + _rx_ck_a; diff --git a/apps/drivers/gps/mtk.h b/apps/drivers/gps/mtk.h index e436371958..39063beabd 100644 --- a/apps/drivers/gps/mtk.h +++ b/apps/drivers/gps/mtk.h @@ -50,6 +50,9 @@ #define WAAS_ON "$PMTK301,2*2E\r\n" #define MTK_NAVTHRES_OFF "$PMTK397,0*23\r\n" +#define MTK_TIMEOUT_5HZ 400 +#define MTK_BAUDRATE 38400 + typedef enum { MTK_DECODE_UNINIT = 0, MTK_DECODE_GOT_CK_A = 1, @@ -64,16 +67,16 @@ typedef struct { int32_t latitude; ///< Latitude in degrees * 10^7 int32_t longitude; ///< Longitude in degrees * 10^7 uint32_t msl_altitude; ///< MSL altitude in meters * 10^2 - uint32_t ground_speed; ///< FIXME SPEC UNCLEAR - int32_t heading; - uint8_t satellites; - uint8_t fix_type; + uint32_t ground_speed; ///< velocity in m/s + int32_t heading; ///< heading in degrees * 10^2 + uint8_t satellites; ///< number of sattelites used + uint8_t fix_type; ///< fix type: XXX correct for that uint32_t date; uint32_t utc_time; - uint16_t hdop; + uint16_t hdop; ///< horizontal dilution of position (without unit) uint8_t ck_a; uint8_t ck_b; -} type_gps_mtk_packet; +} gps_mtk_packet_t; #pragma pack(pop) @@ -84,23 +87,31 @@ class MTK : public GPS_Helper public: MTK(); ~MTK(); - void reset(void); - void configure(const int &fd, bool &baudrate_changed, unsigned &baudrate); - void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated); + int receive(const int &fd, struct vehicle_gps_position_s &gps_position); + int configure(const int &fd, unsigned &baudrate); private: + /** + * Parse the binary MTK packet + */ + int parse_char(uint8_t b, gps_mtk_packet_t &packet); + + /** + * Handle the package once it has arrived + */ + void handle_message(gps_mtk_packet_t &packet, struct vehicle_gps_position_s &gps_position); + /** * Reset the parse state machine for a fresh start */ - void decodeInit(void); + void decode_init(void); /** * While parsing add every byte (except the sync bytes) to the checksum */ - void addByteToChecksum(uint8_t); + void add_byte_to_checksum(uint8_t); mtk_decode_state_t _decode_state; - bool _config_sent; uint8_t _mtk_revision; uint8_t _rx_buffer[MTK_RECV_BUFFER_SIZE]; unsigned _rx_count; From df6cf142e7d67fa8c868245ff144f4e1d4ebdfb3 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 8 Feb 2013 11:05:57 -0800 Subject: [PATCH 20/20] Another rewrite: most of the polling, reading and writing is now inside the GPS classes --- apps/drivers/drv_gps.h | 3 +- apps/drivers/gps/gps.cpp | 62 +- apps/drivers/gps/gps_helper.cpp | 2 + apps/drivers/gps/gps_helper.h | 4 +- apps/drivers/gps/mtk.cpp | 69 ++- apps/drivers/gps/mtk.h | 10 +- apps/drivers/gps/ubx.cpp | 968 ++++++++++++++++---------------- apps/drivers/gps/ubx.h | 32 +- 8 files changed, 583 insertions(+), 567 deletions(-) diff --git a/apps/drivers/drv_gps.h b/apps/drivers/drv_gps.h index 67248efcd9..1dda8ef0b8 100644 --- a/apps/drivers/drv_gps.h +++ b/apps/drivers/drv_gps.h @@ -49,7 +49,8 @@ #define GPS_DEVICE_PATH "/dev/gps" typedef enum { - GPS_DRIVER_MODE_UBX = 0, + GPS_DRIVER_MODE_NONE = 0, + GPS_DRIVER_MODE_UBX, GPS_DRIVER_MODE_MTK, GPS_DRIVER_MODE_NMEA, } gps_driver_mode_t; diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index 76b5f45336..6d7cfcc688 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -36,10 +36,7 @@ * Driver for the GPS on a serial port */ -#include - -#include - +#include #include #include #include @@ -54,30 +51,24 @@ #include #include #include - +#include #include -#include - #include - #include - +#include #include #include #include - #include - +#include #include -//#include "ubx.h" +#include "ubx.h" #include "mtk.h" -#define SEND_BUFFER_LENGTH 100 -#define TIMEOUT 1000000 //1s -#define NUMBER_OF_TRIES 5 -#define CONFIG_TIMEOUT 2000000 +#define TIMEOUT_5HZ 400 +#define RATE_MEASUREMENT_PERIOD 5000000 /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -170,7 +161,7 @@ GPS::GPS(const char* uart_path) : _task_should_exit(false), _healthy(false), _mode_changed(false), - _mode(GPS_DRIVER_MODE_MTK), + _mode(GPS_DRIVER_MODE_UBX), _Helper(nullptr), _report_pub(-1), _rate(0.0f) @@ -279,12 +270,11 @@ GPS::task_main() } switch (_mode) { -// case GPS_DRIVER_MODE_UBX: -// _Helper = new UBX(); -// break; + case GPS_DRIVER_MODE_UBX: + _Helper = new UBX(_serial_fd, &_report); + break; case GPS_DRIVER_MODE_MTK: - printf("try new mtk\n"); - _Helper = new MTK(); + _Helper = new MTK(_serial_fd, &_report); break; case GPS_DRIVER_MODE_NMEA: //_Helper = new NMEA(); //TODO: add NMEA @@ -292,11 +282,11 @@ GPS::task_main() default: break; } - // XXX unlock/lock makes sense? unlock(); - if (_Helper->configure(_serial_fd, _baudrate) == 0) { - - while (_Helper->receive(_serial_fd, _report) > 0 && !_task_should_exit) { + if (_Helper->configure(_baudrate) == 0) { + unlock(); + while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) { +// lock(); /* opportunistic publishing - else invalid data would end up on the bus */ if (_report_pub > 0) { orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); @@ -307,7 +297,7 @@ GPS::task_main() last_rate_count++; /* measure update rate every 5 seconds */ - if (hrt_absolute_time() - last_rate_measurement > 5000000) { + if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) { _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f); last_rate_measurement = hrt_absolute_time(); last_rate_count = 0; @@ -323,8 +313,26 @@ GPS::task_main() _healthy = false; _rate = 0.0f; } + + lock(); } lock(); + + /* select next mode */ + switch (_mode) { + case GPS_DRIVER_MODE_UBX: + _mode = GPS_DRIVER_MODE_MTK; + break; + case GPS_DRIVER_MODE_MTK: + _mode = GPS_DRIVER_MODE_UBX; + break; + // case GPS_DRIVER_MODE_NMEA: + // _mode = GPS_DRIVER_MODE_UBX; + // break; + default: + break; + } + } debug("exiting"); diff --git a/apps/drivers/gps/gps_helper.cpp b/apps/drivers/gps/gps_helper.cpp index 2caa82af15..9c1fad5691 100644 --- a/apps/drivers/gps/gps_helper.cpp +++ b/apps/drivers/gps/gps_helper.cpp @@ -57,6 +57,8 @@ GPS_Helper::set_baudrate(const int &fd, unsigned baud) case 115200: speed = B115200; break; + warnx("try baudrate: %d\n", speed); + default: warnx("ERROR: Unsupported baudrate: %d\n", baud); return -EINVAL; diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h index 537ca819ce..f3d3bc40b3 100644 --- a/apps/drivers/gps/gps_helper.h +++ b/apps/drivers/gps/gps_helper.h @@ -44,8 +44,8 @@ class GPS_Helper { public: - virtual int configure(const int &fd, unsigned &baud) = 0; - virtual int receive(const int &fd, struct vehicle_gps_position_s &gps_position) = 0; + virtual int configure(unsigned &baud) = 0; + virtual int receive(unsigned timeout) = 0; int set_baudrate(const int &fd, unsigned baud); }; diff --git a/apps/drivers/gps/mtk.cpp b/apps/drivers/gps/mtk.cpp index 4ccbbfbe4a..4762bd503a 100644 --- a/apps/drivers/gps/mtk.cpp +++ b/apps/drivers/gps/mtk.cpp @@ -47,7 +47,9 @@ #include "mtk.h" -MTK::MTK() : +MTK::MTK(const int &fd, struct vehicle_gps_position_s *gps_position) : +_fd(fd), +_gps_position(gps_position), _mtk_revision(0) { decode_init(); @@ -58,40 +60,40 @@ MTK::~MTK() } int -MTK::configure(const int &fd, unsigned &baudrate) +MTK::configure(unsigned &baudrate) { /* set baudrate first */ - if (GPS_Helper::set_baudrate(fd, MTK_BAUDRATE) != 0) + if (GPS_Helper::set_baudrate(_fd, MTK_BAUDRATE) != 0) return -1; baudrate = MTK_BAUDRATE; /* Write config messages, don't wait for an answer */ - if (strlen(MTK_OUTPUT_5HZ) != write(fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) { + if (strlen(MTK_OUTPUT_5HZ) != write(_fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) { warnx("mtk: config write failed"); return -1; } usleep(10000); - if (strlen(MTK_SET_BINARY) != write(fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) { + if (strlen(MTK_SET_BINARY) != write(_fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) { warnx("mtk: config write failed"); return -1; } usleep(10000); - if (strlen(SBAS_ON) != write(fd, SBAS_ON, strlen(SBAS_ON))) { + if (strlen(SBAS_ON) != write(_fd, SBAS_ON, strlen(SBAS_ON))) { warnx("mtk: config write failed"); return -1; } usleep(10000); - if (strlen(WAAS_ON) != write(fd, WAAS_ON, strlen(WAAS_ON))) { + if (strlen(WAAS_ON) != write(_fd, WAAS_ON, strlen(WAAS_ON))) { warnx("mtk: config write failed"); return -1; } usleep(10000); - if (strlen(MTK_NAVTHRES_OFF) != write(fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) { + if (strlen(MTK_NAVTHRES_OFF) != write(_fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) { warnx("mtk: config write failed"); return -1; } @@ -100,16 +102,19 @@ MTK::configure(const int &fd, unsigned &baudrate) } int -MTK::receive(const int &fd, struct vehicle_gps_position_s &gps_position) +MTK::receive(unsigned timeout) { /* poll descriptor */ pollfd fds[1]; - fds[0].fd = fd; + fds[0].fd = _fd; fds[0].events = POLLIN; uint8_t buf[32]; gps_mtk_packet_t packet; + /* timeout additional to poll */ + uint64_t time_started = hrt_absolute_time(); + int j = 0; ssize_t count = 0; @@ -120,9 +125,13 @@ MTK::receive(const int &fd, struct vehicle_gps_position_s &gps_position) /* pass received bytes to the packet decoder */ while (j < count) { if (parse_char(buf[j], packet) > 0) { - handle_message(packet, gps_position); + handle_message(packet); return 1; } + /* in case we keep trying but only get crap from GPS */ + if (time_started + timeout*1000 < hrt_absolute_time() ) { + return -1; + } j++; } /* everything is read */ @@ -130,7 +139,7 @@ MTK::receive(const int &fd, struct vehicle_gps_position_s &gps_position) } /* then poll for new data */ - int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), MTK_TIMEOUT_5HZ); + int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout); if (ret < 0) { /* something went wrong when polling */ @@ -148,7 +157,7 @@ MTK::receive(const int &fd, struct vehicle_gps_position_s &gps_position) * won't block even on a blocking device. If more bytes are * available, we'll go back to poll() again... */ - count = ::read(fd, buf, sizeof(buf)); + count = ::read(_fd, buf, sizeof(buf)); } } } @@ -212,26 +221,26 @@ MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet) } void -MTK::handle_message(gps_mtk_packet_t &packet, struct vehicle_gps_position_s &gps_position) +MTK::handle_message(gps_mtk_packet_t &packet) { if (_mtk_revision == 16) { - gps_position.lat = packet.latitude * 10; // from degrees*1e6 to degrees*1e7 - gps_position.lon = packet.longitude * 10; // from degrees*1e6 to degrees*1e7 + _gps_position->lat = packet.latitude * 10; // from degrees*1e6 to degrees*1e7 + _gps_position->lon = packet.longitude * 10; // from degrees*1e6 to degrees*1e7 } else if (_mtk_revision == 19) { - gps_position.lat = packet.latitude; // both degrees*1e7 - gps_position.lon = packet.longitude; // both degrees*1e7 + _gps_position->lat = packet.latitude; // both degrees*1e7 + _gps_position->lon = packet.longitude; // both degrees*1e7 } else { warnx("mtk: unknown revision"); - gps_position.lat = 0; - gps_position.lon = 0; + _gps_position->lat = 0; + _gps_position->lon = 0; } - gps_position.alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm - gps_position.fix_type = packet.fix_type; - gps_position.eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit - gps_position.epv_m = 0.0; //unknown in mtk custom mode - gps_position.vel_m_s = ((float)packet.ground_speed)*1e-2f; // from cm/s to m/s - gps_position.cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad - gps_position.satellites_visible = packet.satellites; + _gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm + _gps_position->fix_type = packet.fix_type; + _gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit + _gps_position->epv_m = 0.0; //unknown in mtk custom mode + _gps_position->vel_m_s = ((float)packet.ground_speed)*1e-2f; // from cm/s to m/s + _gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad + _gps_position->satellites_visible = packet.satellites; /* convert time and date information to unix timestamp */ struct tm timeinfo; //TODO: test this conversion @@ -250,9 +259,9 @@ MTK::handle_message(gps_mtk_packet_t &packet, struct vehicle_gps_position_s &gps timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3; time_t epoch = mktime(&timeinfo); - gps_position.time_gps_usec = epoch * 1e6; //TODO: test this - gps_position.time_gps_usec += timeinfo_conversion_temp * 1e3; - gps_position.timestamp_position = gps_position.timestamp_time = hrt_absolute_time(); + _gps_position->time_gps_usec = epoch * 1e6; //TODO: test this + _gps_position->time_gps_usec += timeinfo_conversion_temp * 1e3; + _gps_position->timestamp_position = _gps_position->timestamp_time = hrt_absolute_time(); return; } diff --git a/apps/drivers/gps/mtk.h b/apps/drivers/gps/mtk.h index 39063beabd..d4e390b01b 100644 --- a/apps/drivers/gps/mtk.h +++ b/apps/drivers/gps/mtk.h @@ -85,10 +85,10 @@ typedef struct { class MTK : public GPS_Helper { public: - MTK(); + MTK(const int &fd, struct vehicle_gps_position_s *gps_position); ~MTK(); - int receive(const int &fd, struct vehicle_gps_position_s &gps_position); - int configure(const int &fd, unsigned &baudrate); + int receive(unsigned timeout); + int configure(unsigned &baudrate); private: /** @@ -99,7 +99,7 @@ private: /** * Handle the package once it has arrived */ - void handle_message(gps_mtk_packet_t &packet, struct vehicle_gps_position_s &gps_position); + void handle_message(gps_mtk_packet_t &packet); /** * Reset the parse state machine for a fresh start @@ -111,6 +111,8 @@ private: */ void add_byte_to_checksum(uint8_t); + int _fd; + struct vehicle_gps_position_s *_gps_position; mtk_decode_state_t _decode_state; uint8_t _mtk_revision; uint8_t _rx_buffer[MTK_RECV_BUFFER_SIZE]; diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index 8e2396564d..74cbc5aaf3 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -37,6 +37,7 @@ #include #include +#include #include #include #include @@ -47,172 +48,251 @@ #include "ubx.h" +#define UBX_CONFIG_TIMEOUT 100 -UBX::UBX() : -_config_state(UBX_CONFIG_STATE_PRT), +UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) : +_fd(fd), +_gps_position(gps_position), _waiting_for_ack(false) { - reset(); + decode_init(); } UBX::~UBX() { } -void -UBX::reset() +int +UBX::configure(unsigned &baudrate) { - decodeInit(); - _config_state = UBX_CONFIG_STATE_PRT; - _waiting_for_ack = false; + _waiting_for_ack = true; + + /* try different baudrates */ + const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200}; + + for (int baud_i = 0; baud_i < 5; baud_i++) { + baudrate = baudrates_to_try[baud_i]; + set_baudrate(_fd, baudrate); + + /* Send a CFG-PRT message to set the UBX protocol for in and out + * and leave the baudrate as it is, we just want an ACK-ACK from this + */ + type_gps_bin_cfg_prt_packet_t cfg_prt_packet; + /* Set everything else of the packet to 0, otherwise the module wont accept it */ + memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); + + _clsID_needed = UBX_CLASS_CFG; + _msgID_needed = UBX_MESSAGE_CFG_PRT; + + /* Define the package contents, don't change the baudrate */ + cfg_prt_packet.clsID = UBX_CLASS_CFG; + cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; + cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; + cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; + cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; + cfg_prt_packet.baudRate = baudrate; + cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; + cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; + + send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); + + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } + + /* Send a CFG-PRT message again, this time change the baudrate */ + + cfg_prt_packet.clsID = UBX_CLASS_CFG; + cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; + cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; + cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; + cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; + cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE; + cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; + cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; + + send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); + if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) { + set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE); + baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE; + } + + /* no ack is ecpected here, keep going configuring */ + + /* send a CFT-RATE message to define update rate */ + type_gps_bin_cfg_rate_packet_t cfg_rate_packet; + memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet)); + + _clsID_needed = UBX_CLASS_CFG; + _msgID_needed = UBX_MESSAGE_CFG_RATE; + + cfg_rate_packet.clsID = UBX_CLASS_CFG; + cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE; + cfg_rate_packet.length = UBX_CFG_RATE_LENGTH; + cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASRATE; + cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE; + cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF; + + send_config_packet(_fd, (uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet)); + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } + + /* send a NAV5 message to set the options for the internal filter */ + type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet; + memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet)); + + _clsID_needed = UBX_CLASS_CFG; + _msgID_needed = UBX_MESSAGE_CFG_NAV5; + + cfg_nav5_packet.clsID = UBX_CLASS_CFG; + cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5; + cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH; + cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK; + cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL; + cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE; + + send_config_packet(_fd, (uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet)); + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } + + type_gps_bin_cfg_msg_packet_t cfg_msg_packet; + memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet)); + + _clsID_needed = UBX_CLASS_CFG; + _msgID_needed = UBX_MESSAGE_CFG_MSG; + + cfg_msg_packet.clsID = UBX_CLASS_CFG; + cfg_msg_packet.msgID = UBX_MESSAGE_CFG_MSG; + cfg_msg_packet.length = UBX_CFG_MSG_LENGTH; + /* Choose fast 5Hz rate for all messages except SVINFO which is big and not important */ + cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_5HZ; + + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_POSLLH; + + send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } + + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC; + + send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } + + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO; + /* For satelites info 1Hz is enough */ + cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_1HZ; + + send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } + + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SOL; + + send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } + + cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; + cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_VELNED; + + send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); + if (receive(UBX_CONFIG_TIMEOUT) < 0) { + /* try next baudrate */ + continue; + } +// cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; +// cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP; + +// cfg_msg_packet.msgClass_payload = UBX_CLASS_RXM; +// cfg_msg_packet.msgID_payload = UBX_MESSAGE_RXM_SVSI; + + _waiting_for_ack = false; + return 0; + } + return -1; } -void -UBX::configure(const int &fd, bool &baudrate_changed, unsigned &baudrate) +int +UBX::receive(unsigned timeout) { - /* Only send a new config message when we got the ACK of the last one, - * otherwise we might not configure all the messages because the ACK comes from an older/previos CFD command - * reason being that the ACK only includes CFG-MSG but not to which NAV MSG it belongs. - */ - if (!_waiting_for_ack) { - _waiting_for_ack = true; - if (_config_state == UBX_CONFIG_STATE_CONFIGURED) { - /* This should never happen, the parser should set the flag, - * if it should be reconfigured, reset() should be called first. - */ - warnx("ubx: already configured"); - _waiting_for_ack = false; - return; - } else if (_config_state == UBX_CONFIG_STATE_PRT) { + /* poll descriptor */ + pollfd fds[1]; + fds[0].fd = _fd; + fds[0].events = POLLIN; - /* Send a CFG-PRT message to set the UBX protocol for in and out - * and leave the baudrate as it is, we just want an ACK-ACK from this - */ - type_gps_bin_cfg_prt_packet_t cfg_prt_packet; - /* Set everything else of the packet to 0, otherwise the module wont accept it */ - memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); + uint8_t buf[32]; - /* Define the package contents, don't change the baudrate */ - cfg_prt_packet.clsID = UBX_CLASS_CFG; - cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; - cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; - cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; - cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; - cfg_prt_packet.baudRate = baudrate; - cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; - cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; + /* timeout additional to poll */ + uint64_t time_started = hrt_absolute_time(); - sendConfigPacket(fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); + int j = 0; + ssize_t count = 0; - } else if (_config_state == UBX_CONFIG_STATE_PRT_NEW_BAUDRATE) { + while (true) { - /* Send a CFG-PRT message again, this time change the baudrate */ - type_gps_bin_cfg_prt_packet_t cfg_prt_packet; - memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); - - cfg_prt_packet.clsID = UBX_CLASS_CFG; - cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; - cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; - cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; - cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; - cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE; - cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; - cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; - - sendConfigPacket(fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet)); - - /* If the new baudrate will be different from the current one, we should report that back to the driver */ - if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) { - baudrate=UBX_CFG_PRT_PAYLOAD_BAUDRATE; - baudrate_changed = true; - /* Don't wait for an ACK, we're switching baudrate and we might never get, - * after that, start fresh */ - reset(); + /* pass received bytes to the packet decoder */ + while (j < count) { + if (parse_char(buf[j]) > 0) { + /* return to configure during configuration or to the gps driver during normal work + * if a packet has arrived */ + if (handle_message() > 0) + return 1; } - - } else if (_config_state == UBX_CONFIG_STATE_RATE) { - - /* send a CFT-RATE message to define update rate */ - type_gps_bin_cfg_rate_packet_t cfg_rate_packet; - memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet)); - - cfg_rate_packet.clsID = UBX_CLASS_CFG; - cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE; - cfg_rate_packet.length = UBX_CFG_RATE_LENGTH; - cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASRATE; - cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE; - cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF; - - sendConfigPacket(fd, (uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet)); - - } else if (_config_state == UBX_CONFIG_STATE_NAV5) { - /* send a NAV5 message to set the options for the internal filter */ - type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet; - memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet)); - - cfg_nav5_packet.clsID = UBX_CLASS_CFG; - cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5; - cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH; - cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK; - cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL; - cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE; - - sendConfigPacket(fd, (uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet)); - - } else { - /* Catch the remaining config states here, they all need the same packet type */ - - type_gps_bin_cfg_msg_packet_t cfg_msg_packet; - memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet)); - - cfg_msg_packet.clsID = UBX_CLASS_CFG; - cfg_msg_packet.msgID = UBX_MESSAGE_CFG_MSG; - cfg_msg_packet.length = UBX_CFG_MSG_LENGTH; - /* Choose fast 5Hz rate for all messages except SVINFO which is big and not important */ - cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_5HZ; - - switch (_config_state) { - case UBX_CONFIG_STATE_MSG_NAV_POSLLH: - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_POSLLH; - break; - case UBX_CONFIG_STATE_MSG_NAV_TIMEUTC: - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC; - break; -// case UBX_CONFIG_STATE_MSG_NAV_DOP: -// cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; -// cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP; -// break; - case UBX_CONFIG_STATE_MSG_NAV_SVINFO: - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO; - /* For satelites info 1Hz is enough */ - cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_1HZ; - break; - case UBX_CONFIG_STATE_MSG_NAV_SOL: - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SOL; - break; - case UBX_CONFIG_STATE_MSG_NAV_VELNED: - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_VELNED; - break; -// case UBX_CONFIG_STATE_MSG_RXM_SVSI: -// cfg_msg_packet.msgClass_payload = UBX_CLASS_RXM; -// cfg_msg_packet.msgID_payload = UBX_MESSAGE_RXM_SVSI; -// break; - default: - break; + /* in case we keep trying but only get crap from GPS */ + if (time_started + timeout*1000 < hrt_absolute_time() ) { + return -1; } + j++; + } - sendConfigPacket(fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); + /* everything is read */ + j = count = 0; + + /* then poll for new data */ + int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout); + + if (ret < 0) { + /* something went wrong when polling */ + return -1; + + } else if (ret == 0) { + /* Timeout */ + return -1; + + } else if (ret > 0) { + /* if we have new data from GPS, go handle it */ + if (fds[0].revents & POLLIN) { + /* + * We are here because poll says there is some data, so this + * won't block even on a blocking device. If more bytes are + * available, we'll go back to poll() again... + */ + count = ::read(_fd, buf, sizeof(buf)); + } } } } -void -UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_needed, bool &pos_updated) +int +UBX::parse_char(uint8_t b) { switch (_decode_state) { /* First, look for sync1 */ @@ -227,13 +307,13 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ _decode_state = UBX_DECODE_GOT_SYNC2; } else { /* Second start symbol was wrong, reset state machine */ - decodeInit(); + decode_init(); } break; /* Now look for class */ case UBX_DECODE_GOT_SYNC2: /* everything except sync1 and sync2 needs to be added to the checksum */ - addByteToChecksum(b); + add_byte_to_checksum(b); /* check for known class */ switch (b) { case UBX_CLASS_ACK: @@ -256,12 +336,12 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ _message_class = CFG; break; default: //unknown class: reset state machine - decodeInit(); + decode_init(); break; } break; case UBX_DECODE_GOT_CLASS: - addByteToChecksum(b); + add_byte_to_checksum(b); switch (_message_class) { case NAV: switch (b) { @@ -296,7 +376,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ break; default: //unknown class: reset state machine, should not happen - decodeInit(); + decode_init(); break; } break; @@ -308,7 +388,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ // break; // // default: //unknown class: reset state machine, should not happen -// decodeInit(); +// decode_init(); // break; // } // break; @@ -321,7 +401,7 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ break; default: //unknown class: reset state machine, should not happen - decodeInit(); + decode_init(); break; } break; @@ -337,384 +417,282 @@ UBX::parse(uint8_t b, struct vehicle_gps_position_s *gps_position, bool &config_ _message_id = ACK_NAK; break; default: //unknown class: reset state machine, should not happen - decodeInit(); + decode_init(); break; } break; default: //should not happen because we set the class warnx("UBX Error, we set a class that we don't know"); - decodeInit(); - config_needed = true; + decode_init(); +// config_needed = true; break; } break; case UBX_DECODE_GOT_MESSAGEID: - addByteToChecksum(b); + add_byte_to_checksum(b); _payload_size = b; //this is the first length byte _decode_state = UBX_DECODE_GOT_LENGTH1; break; case UBX_DECODE_GOT_LENGTH1: - addByteToChecksum(b); + add_byte_to_checksum(b); _payload_size += b << 8; // here comes the second byte of length _decode_state = UBX_DECODE_GOT_LENGTH2; break; case UBX_DECODE_GOT_LENGTH2: /* Add to checksum if not yet at checksum byte */ if (_rx_count < _payload_size) - addByteToChecksum(b); + add_byte_to_checksum(b); _rx_buffer[_rx_count] = b; /* once the payload has arrived, we can process the information */ if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes - switch (_message_id) { //this enum is unique for all ids --> no need to check the class - case NAV_POSLLH: { -// printf("GOT NAV_POSLLH MESSAGE\n"); - gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer; - //Check if checksum is valid and the store the gps information - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - gps_position->lat = packet->lat; - gps_position->lon = packet->lon; - gps_position->alt = packet->height_msl; - - gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m - gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m - - /* Add timestamp to finish the report */ - gps_position->timestamp_position = hrt_absolute_time(); - - /* set flag to trigger publishing of new position */ - pos_updated = true; - - } else { - warnx("NAV_POSLLH: checksum invalid"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; - } - - case NAV_SOL: { -// printf("GOT NAV_SOL MESSAGE\n"); - gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer; - - //Check if checksum is valid and the store the gps information - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - - gps_position->fix_type = packet->gpsFix; - gps_position->s_variance_m_s = packet->sAcc; - gps_position->p_variance_m = packet->pAcc; - - gps_position->timestamp_variance = hrt_absolute_time(); - - } else { - warnx("NAV_SOL: checksum invalid"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; - } - -// case NAV_DOP: { -//// printf("GOT NAV_DOP MESSAGE\n"); -// gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer; -// -// //Check if checksum is valid and the store the gps information -// if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { -// -// gps_position->eph_m = packet->hDOP; -// gps_position->epv = packet->vDOP; -// -// gps_position->timestamp_posdilution = hrt_absolute_time(); -// -// _new_nav_dop = true; -// -// } else { -// warnx("NAV_DOP: checksum invalid"); -// } -// -// // Reset state machine to decode next packet -// decodeInit(); -// break; -// } - - case NAV_TIMEUTC: { -// printf("GOT NAV_TIMEUTC MESSAGE\n"); - gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer; - - //Check if checksum is valid and the store the gps information - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - //convert to unix timestamp - struct tm timeinfo; - timeinfo.tm_year = packet->year - 1900; - timeinfo.tm_mon = packet->month - 1; - timeinfo.tm_mday = packet->day; - timeinfo.tm_hour = packet->hour; - timeinfo.tm_min = packet->min; - timeinfo.tm_sec = packet->sec; - - time_t epoch = mktime(&timeinfo); - - gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this - gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); - - gps_position->timestamp_time = hrt_absolute_time(); - - } else { - warnx("NAV_TIMEUTC: checksum invalid"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; - } - - case NAV_SVINFO: { -// printf("GOT NAV_SVINFO MESSAGE\n"); - - //this is a more complicated message: the length depends on the number of satellites. This number is extracted from the first part of the message - const int length_part1 = 8; - char _rx_buffer_part1[length_part1]; - memcpy(_rx_buffer_part1, _rx_buffer, length_part1); - gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer_part1; - - //read checksum - const int length_part3 = 2; - char _rx_buffer_part3[length_part3]; - memcpy(_rx_buffer_part3, &(_rx_buffer[_rx_count - 1]), length_part3); - gps_bin_nav_svinfo_part3_packet_t *packet_part3 = (gps_bin_nav_svinfo_part3_packet_t *) _rx_buffer_part3; - - //Check if checksum is valid and then store the gps information - if (_rx_ck_a == packet_part3->ck_a && _rx_ck_b == packet_part3->ck_b) { - //definitions needed to read numCh elements from the buffer: - const int length_part2 = 12; - gps_bin_nav_svinfo_part2_packet_t *packet_part2; - char _rx_buffer_part2[length_part2]; //for temporal storage - - uint8_t satellites_used = 0; - int i; - - for (i = 0; i < packet_part1->numCh; i++) { //for each channel - - /* Get satellite information from the buffer */ - memcpy(_rx_buffer_part2, &(_rx_buffer[length_part1 + i * length_part2]), length_part2); - packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) _rx_buffer_part2; - - - /* Write satellite information in the global storage */ - gps_position->satellite_prn[i] = packet_part2->svid; - - //if satellite information is healthy store the data - uint8_t unhealthy = packet_part2->flags & 1 << 4; //flags is a bitfield - - if (!unhealthy) { - if ((packet_part2->flags) & 1) { //flags is a bitfield - gps_position->satellite_used[i] = 1; - satellites_used++; - - } else { - gps_position->satellite_used[i] = 0; - } - - gps_position->satellite_snr[i] = packet_part2->cno; - gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev); - gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f); - - } else { - gps_position->satellite_used[i] = 0; - gps_position->satellite_snr[i] = 0; - gps_position->satellite_elevation[i] = 0; - gps_position->satellite_azimuth[i] = 0; - } - - } - - for (i = packet_part1->numCh; i < 20; i++) { //these channels are unused - /* Unused channels have to be set to zero for e.g. MAVLink */ - gps_position->satellite_prn[i] = 0; - gps_position->satellite_used[i] = 0; - gps_position->satellite_snr[i] = 0; - gps_position->satellite_elevation[i] = 0; - gps_position->satellite_azimuth[i] = 0; - } - gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones - - /* set timestamp if any sat info is available */ - if (packet_part1->numCh > 0) { - gps_position->satellite_info_available = true; - } else { - gps_position->satellite_info_available = false; - } - gps_position->timestamp_satellites = hrt_absolute_time(); - - } else { - warnx("NAV_SVINFO: checksum invalid"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; - } - - case NAV_VELNED: { -// printf("GOT NAV_VELNED MESSAGE\n"); - gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer; - - //Check if checksum is valid and the store the gps information - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - - gps_position->vel_m_s = (float)packet->speed * 1e-2f; - gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; - gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; - gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; - gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f; - gps_position->vel_ned_valid = true; - gps_position->timestamp_velocity = hrt_absolute_time(); - - } else { - warnx("NAV_VELNED: checksum invalid"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; - } - -// case RXM_SVSI: { -// printf("GOT RXM_SVSI MESSAGE\n"); -// const int length_part1 = 7; -// char _rx_buffer_part1[length_part1]; -// memcpy(_rx_buffer_part1, _rx_buffer, length_part1); -// gps_bin_rxm_svsi_packet_t *packet = (gps_bin_rxm_svsi_packet_t *) _rx_buffer_part1; -// -// //Check if checksum is valid and the store the gps information -// if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) { -// -// gps_position->satellites_visible = packet->numVis; -// gps_position->counter++; -// _last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time(); -// ret = 1; -// -// } else { -// warnx("RXM_SVSI: checksum invalid\n"); -// } -// -// // Reset state machine to decode next packet -// decodeInit(); -// break; -// } - - case ACK_ACK: { -// printf("GOT ACK_ACK\n"); - gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer; - - //Check if checksum is valid - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - - _waiting_for_ack = false; - - switch (_config_state) { - case UBX_CONFIG_STATE_PRT: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_PRT) - _config_state = UBX_CONFIG_STATE_PRT_NEW_BAUDRATE; - break; - case UBX_CONFIG_STATE_PRT_NEW_BAUDRATE: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_PRT) - _config_state = UBX_CONFIG_STATE_RATE; - break; - case UBX_CONFIG_STATE_RATE: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_RATE) - _config_state = UBX_CONFIG_STATE_NAV5; - break; - case UBX_CONFIG_STATE_NAV5: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_NAV5) - _config_state = UBX_CONFIG_STATE_MSG_NAV_POSLLH; - break; - case UBX_CONFIG_STATE_MSG_NAV_POSLLH: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) - _config_state = UBX_CONFIG_STATE_MSG_NAV_TIMEUTC; - break; - case UBX_CONFIG_STATE_MSG_NAV_TIMEUTC: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) - _config_state = UBX_CONFIG_STATE_MSG_NAV_SVINFO; - break; -// case UBX_CONFIG_STATE_MSG_NAV_DOP: -// if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) -// _config_state = UBX_CONFIG_STATE_MSG_NAV_SVINFO; -// break; - case UBX_CONFIG_STATE_MSG_NAV_SVINFO: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) - _config_state = UBX_CONFIG_STATE_MSG_NAV_SOL; - break; - case UBX_CONFIG_STATE_MSG_NAV_SOL: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) - _config_state = UBX_CONFIG_STATE_MSG_NAV_VELNED; - break; - case UBX_CONFIG_STATE_MSG_NAV_VELNED: - if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) - _config_state = UBX_CONFIG_STATE_CONFIGURED; - /* set the flag to tell the driver that configuration was successful */ - config_needed = false; - break; -// case UBX_CONFIG_STATE_MSG_RXM_SVSI: -// if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG) -// _config_state = UBX_CONFIG_STATE_CONFIGURED; -// break; - default: - break; - } - } else { - warnx("ACK_ACK: checksum invalid"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; + /* compare checksum */ + if (_rx_ck_a == _rx_buffer[_rx_count-1] && _rx_ck_b == _rx_buffer[_rx_count]) { + return 1; + } else { + decode_init(); + return -1; + warnx("ubx: Checksum wrong"); } - case ACK_NAK: { -// printf("GOT ACK_NAK\n"); - gps_bin_ack_nak_packet_t *packet = (gps_bin_ack_nak_packet_t *) _rx_buffer; - - //Check if checksum is valid - if (_rx_ck_a == packet->ck_a && _rx_ck_b == packet->ck_b) { - - warnx("UBX: Received: Not Acknowledged"); - /* configuration obviously not successful */ - config_needed = true; - } else { - warnx("ACK_NAK: checksum invalid\n"); - } - - // Reset state machine to decode next packet - decodeInit(); - break; - } - - default: //we don't know the message - warnx("UBX: Unknown message received: %d-%d\n",_message_class,_message_id); - decodeInit(); - - break; - } - } // end if _rx_count high enough - else if (_rx_count < RECV_BUFFER_SIZE) { + return 1; + } else if (_rx_count < RECV_BUFFER_SIZE) { _rx_count++; } else { - warnx("buffer full, restarting"); - decodeInit(); - config_needed = true; + warnx("ubx: buffer full"); + decode_init(); + return -1; } break; default: break; } - return; + return 0; //XXX ? +} + + +int +UBX::handle_message() +{ + int ret = 0; + + switch (_message_id) { //this enum is unique for all ids --> no need to check the class + case NAV_POSLLH: { +// printf("GOT NAV_POSLLH MESSAGE\n"); + if (!_waiting_for_ack) { + gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer; + + _gps_position->lat = packet->lat; + _gps_position->lon = packet->lon; + _gps_position->alt = packet->height_msl; + + _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m + _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m + + /* Add timestamp to finish the report */ + _gps_position->timestamp_position = hrt_absolute_time(); + /* only return 1 when new position is available */ + ret = 1; + } + break; + } + + case NAV_SOL: { +// printf("GOT NAV_SOL MESSAGE\n"); + if (!_waiting_for_ack) { + gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer; + + _gps_position->fix_type = packet->gpsFix; + _gps_position->s_variance_m_s = packet->sAcc; + _gps_position->p_variance_m = packet->pAcc; + + _gps_position->timestamp_variance = hrt_absolute_time(); + } + break; + } + +// case NAV_DOP: { +//// printf("GOT NAV_DOP MESSAGE\n"); +// gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer; +// +// _gps_position->eph_m = packet->hDOP; +// _gps_position->epv = packet->vDOP; +// +// _gps_position->timestamp_posdilution = hrt_absolute_time(); +// +// _new_nav_dop = true; +// +// break; +// } + + case NAV_TIMEUTC: { +// printf("GOT NAV_TIMEUTC MESSAGE\n"); + + if (!_waiting_for_ack) { + gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer; + + //convert to unix timestamp + struct tm timeinfo; + timeinfo.tm_year = packet->year - 1900; + timeinfo.tm_mon = packet->month - 1; + timeinfo.tm_mday = packet->day; + timeinfo.tm_hour = packet->hour; + timeinfo.tm_min = packet->min; + timeinfo.tm_sec = packet->sec; + + time_t epoch = mktime(&timeinfo); + + _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this + _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); + + _gps_position->timestamp_time = hrt_absolute_time(); + } + break; + } + + case NAV_SVINFO: { +// printf("GOT NAV_SVINFO MESSAGE\n"); + + if (!_waiting_for_ack) { + //this is a more complicated message: the length depends on the number of satellites. This number is extracted from the first part of the message + const int length_part1 = 8; + char _rx_buffer_part1[length_part1]; + memcpy(_rx_buffer_part1, _rx_buffer, length_part1); + gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer_part1; + + //read checksum + const int length_part3 = 2; + char _rx_buffer_part3[length_part3]; + memcpy(_rx_buffer_part3, &(_rx_buffer[_rx_count - 1]), length_part3); + + //definitions needed to read numCh elements from the buffer: + const int length_part2 = 12; + gps_bin_nav_svinfo_part2_packet_t *packet_part2; + char _rx_buffer_part2[length_part2]; //for temporal storage + + uint8_t satellites_used = 0; + int i; + + for (i = 0; i < packet_part1->numCh; i++) { //for each channel + + /* Get satellite information from the buffer */ + memcpy(_rx_buffer_part2, &(_rx_buffer[length_part1 + i * length_part2]), length_part2); + packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) _rx_buffer_part2; + + + /* Write satellite information in the global storage */ + _gps_position->satellite_prn[i] = packet_part2->svid; + + //if satellite information is healthy store the data + uint8_t unhealthy = packet_part2->flags & 1 << 4; //flags is a bitfield + + if (!unhealthy) { + if ((packet_part2->flags) & 1) { //flags is a bitfield + _gps_position->satellite_used[i] = 1; + satellites_used++; + + } else { + _gps_position->satellite_used[i] = 0; + } + + _gps_position->satellite_snr[i] = packet_part2->cno; + _gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev); + _gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f); + + } else { + _gps_position->satellite_used[i] = 0; + _gps_position->satellite_snr[i] = 0; + _gps_position->satellite_elevation[i] = 0; + _gps_position->satellite_azimuth[i] = 0; + } + + } + + for (i = packet_part1->numCh; i < 20; i++) { //these channels are unused + /* Unused channels have to be set to zero for e.g. MAVLink */ + _gps_position->satellite_prn[i] = 0; + _gps_position->satellite_used[i] = 0; + _gps_position->satellite_snr[i] = 0; + _gps_position->satellite_elevation[i] = 0; + _gps_position->satellite_azimuth[i] = 0; + } + _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones + + /* set timestamp if any sat info is available */ + if (packet_part1->numCh > 0) { + _gps_position->satellite_info_available = true; + } else { + _gps_position->satellite_info_available = false; + } + _gps_position->timestamp_satellites = hrt_absolute_time(); + } + + break; + } + + case NAV_VELNED: { +// printf("GOT NAV_VELNED MESSAGE\n"); + + if (!_waiting_for_ack) { + gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer; + + _gps_position->vel_m_s = (float)packet->speed * 1e-2f; + _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; + _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; + _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; + _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f; + _gps_position->vel_ned_valid = true; + _gps_position->timestamp_velocity = hrt_absolute_time(); + } + + break; + } + +// case RXM_SVSI: { +// printf("GOT RXM_SVSI MESSAGE\n"); +// const int length_part1 = 7; +// char _rx_buffer_part1[length_part1]; +// memcpy(_rx_buffer_part1, _rx_buffer, length_part1); +// gps_bin_rxm_svsi_packet_t *packet = (gps_bin_rxm_svsi_packet_t *) _rx_buffer_part1; +// +// _gps_position->satellites_visible = packet->numVis; +// _gps_position->counter++; +// _last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time(); +// +// break; +// } + case ACK_ACK: { +// printf("GOT ACK_ACK\n"); + gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer; + + if (_waiting_for_ack) { + if (packet->clsID == _clsID_needed && packet->msgID == _msgID_needed) { + ret = 1; + } + } + } + break; + + case ACK_NAK: { +// printf("GOT ACK_NAK\n"); + warnx("UBX: Received: Not Acknowledged"); + /* configuration obviously not successful */ + ret = -1; + break; + } + + default: //we don't know the message + warnx("UBX: Unknown message received: %d-%d\n",_message_class,_message_id); + ret = -1; + break; + } + // end if _rx_count high enough + decode_init(); + return ret; //XXX? } void -UBX::decodeInit(void) +UBX::decode_init(void) { _rx_ck_a = 0; _rx_ck_b = 0; @@ -726,14 +704,14 @@ UBX::decodeInit(void) } void -UBX::addByteToChecksum(uint8_t b) +UBX::add_byte_to_checksum(uint8_t b) { _rx_ck_a = _rx_ck_a + b; _rx_ck_b = _rx_ck_b + _rx_ck_a; } void -UBX::addChecksumToMessage(uint8_t* message, const unsigned length) +UBX::add_checksum_to_message(uint8_t* message, const unsigned length) { uint8_t ck_a = 0; uint8_t ck_b = 0; @@ -749,12 +727,12 @@ UBX::addChecksumToMessage(uint8_t* message, const unsigned length) } void -UBX::sendConfigPacket(const int &fd, uint8_t *packet, const unsigned length) +UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length) { ssize_t ret = 0; /* Calculate the checksum now */ - addChecksumToMessage(packet, length); + add_checksum_to_message(packet, length); const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2}; diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index c420e83b9e..e3dd1c7ea9 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -86,6 +86,8 @@ #define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ #define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ +#define UBX_MAX_PAYLOAD_LENGTH 500 + // ************ /** the structures of the binary packets */ #pragma pack(push, 1) @@ -337,35 +339,49 @@ typedef enum { class UBX : public GPS_Helper { public: - UBX(); + UBX(const int &fd, struct vehicle_gps_position_s *gps_position); ~UBX(); - void reset(void); - void configure(const int &fd, bool &baudrate_changed, unsigned &baudrate); - void parse(uint8_t, struct vehicle_gps_position_s*, bool &config_needed, bool &pos_updated); + int receive(unsigned timeout); + int configure(unsigned &baudrate); private: + + /** + * Parse the binary MTK packet + */ + int parse_char(uint8_t b); + + /** + * Handle the package once it has arrived + */ + int handle_message(void); + /** * Reset the parse state machine for a fresh start */ - void decodeInit(void); + void decode_init(void); /** * While parsing add every byte (except the sync bytes) to the checksum */ - void addByteToChecksum(uint8_t); + void add_byte_to_checksum(uint8_t); /** * Add the two checksum bytes to an outgoing message */ - void addChecksumToMessage(uint8_t* message, const unsigned length); + void add_checksum_to_message(uint8_t* message, const unsigned length); /** * Helper to send a config packet */ - void sendConfigPacket(const int &fd, uint8_t *packet, const unsigned length); + void send_config_packet(const int &fd, uint8_t *packet, const unsigned length); + int _fd; + struct vehicle_gps_position_s *_gps_position; ubx_config_state_t _config_state; bool _waiting_for_ack; + uint8_t _clsID_needed; + uint8_t _msgID_needed; ubx_decode_state_t _decode_state; uint8_t _rx_buffer[RECV_BUFFER_SIZE]; unsigned _rx_count;