Files
bizhang_-obav/src/drivers/gps/gps.cpp

701 lines
16 KiB
C++
Raw Normal View History

/****************************************************************************
*
* Copyright (c) 2013-2016 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 a serial port
*/
#ifndef __PX4_QURT
#ifdef __PX4_NUTTX
#include <nuttx/clock.h>
#include <nuttx/arch.h>
#endif
#include <fcntl.h>
#endif
#include <sys/types.h>
#include <stdint.h>
#include <stdio.h>
#include <stdbool.h>
#include <stdlib.h>
#include <string.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <px4_config.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/i2c.h>
#include <systemlib/systemlib.h>
#include <systemlib/scheduling_priorities.h>
#include <systemlib/err.h>
#include <drivers/drv_gps.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/satellite_info.h>
#include <board_config.h>
#include "ubx.h"
#include "mtk.h"
2014-09-30 15:44:47 +04:00
#include "ashtech.h"
#define TIMEOUT_5HZ 500
#define RATE_MEASUREMENT_PERIOD 5000000
/* class for dynamic allocation of satellite info data */
class GPS_Sat_Info
{
public:
struct satellite_info_s _data;
};
class GPS
{
public:
GPS(const char *uart_path, bool fake_gps, bool enable_sat_info);
virtual ~GPS();
virtual int init();
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
private:
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
2014-07-02 11:39:56 +02:00
volatile int _task; ///< worker task
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
GPS_Helper *_Helper; ///< instance of GPS parser
GPS_Sat_Info *_Sat_Info; ///< instance of GPS sat info data object
struct vehicle_gps_position_s _report_gps_pos; ///< uORB topic for gps position
orb_advert_t _report_gps_pos_pub; ///< uORB pub for gps position
struct satellite_info_s *_p_report_sat_info; ///< pointer to uORB topic for satellite info
orb_advert_t _report_sat_info_pub; ///< uORB pub for satellite info
float _rate; ///< position update rate
2014-01-11 00:46:45 +01:00
bool _fake_gps; ///< fake gps output
/**
* 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: main GPS thread that configures the GPS and parses incoming data, always running
*/
2013-02-04 17:55:58 +01:00
void task_main(void);
2013-02-04 17:55:58 +01:00
/**
* Set the baudrate of the UART to the GPS
2013-02-04 17:55:58 +01:00
*/
int set_baudrate(unsigned baud);
/**
* Send a reset command to the GPS
*/
2013-02-04 17:55:58 +01:00
void cmd_reset();
};
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int gps_main(int argc, char *argv[]);
namespace
{
2015-02-11 17:57:33 +01:00
GPS *g_dev = nullptr;
}
GPS::GPS(const char *uart_path, bool fake_gps, bool enable_sat_info) :
_task_should_exit(false),
_healthy(false),
_mode_changed(false),
_mode(GPS_DRIVER_MODE_UBX),
2013-02-04 17:55:58 +01:00
_Helper(nullptr),
_Sat_Info(nullptr),
_report_gps_pos_pub(nullptr),
_p_report_sat_info(nullptr),
_report_sat_info_pub(nullptr),
2014-01-11 00:46:45 +01:00
_rate(0.0f),
_fake_gps(fake_gps)
{
/* 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_gps_pos, 0, sizeof(_report_gps_pos));
/* create satellite info data object if requested */
if (enable_sat_info) {
_Sat_Info = new GPS_Sat_Info();
_p_report_sat_info = &_Sat_Info->_data;
memset(_p_report_sat_info, 0, sizeof(*_p_report_sat_info));
}
}
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 */
2015-10-19 13:16:11 +02:00
if (_task != -1) {
px4_task_delete(_task);
2015-10-19 13:16:11 +02:00
}
2016-04-06 14:26:10 +02:00
if (_Sat_Info) {
delete(_Sat_Info);
}
g_dev = nullptr;
}
int
GPS::init()
{
/* start the GPS driver worker task */
_task = px4_task_spawn_cmd("gps", SCHED_DEFAULT,
SCHED_PRIORITY_SLOW_DRIVER, 1200, (px4_main_t)&GPS::task_main_trampoline, nullptr);
if (_task < 0) {
PX4_WARN("task start failed: %d", errno);
return -errno;
}
return OK;
}
void
GPS::task_main_trampoline(void *arg)
{
g_dev->task_main();
}
void
GPS::task_main()
{
/* open the serial port */
_serial_fd = ::open(_port, O_RDWR);
if (_serial_fd < 0) {
PX4_ERR("GPS: failed to open serial port: %s err: %d", _port, errno);
2013-02-04 17:55:58 +01:00
/* tell the dtor that we are exiting, set error code */
_task = -1;
px4_task_exit(1);
}
#ifndef __PX4_QURT
// TODO: this call is not supported on Snapdragon just yet.
// However it seems to be nonblocking anyway and working.
int flags = fcntl(_serial_fd, F_GETFL, 0);
fcntl(_serial_fd, F_SETFL, flags | O_NONBLOCK);
#endif
2013-02-04 17:55:58 +01:00
uint64_t last_rate_measurement = hrt_absolute_time();
unsigned last_rate_count = 0;
/* loop handling received serial bytes and also configuring in between */
while (!_task_should_exit) {
2014-01-11 00:46:45 +01:00
if (_fake_gps) {
2015-02-13 14:29:59 +01:00
_report_gps_pos.timestamp_position = hrt_absolute_time();
_report_gps_pos.lat = (int32_t)47.378301e7f;
_report_gps_pos.lon = (int32_t)8.538777e7f;
_report_gps_pos.alt = (int32_t)1200e3f;
_report_gps_pos.timestamp_variance = hrt_absolute_time();
_report_gps_pos.s_variance_m_s = 10.0f;
_report_gps_pos.c_variance_rad = 0.1f;
_report_gps_pos.fix_type = 3;
_report_gps_pos.eph = 0.9f;
_report_gps_pos.epv = 1.8f;
_report_gps_pos.timestamp_velocity = hrt_absolute_time();
_report_gps_pos.vel_n_m_s = 0.0f;
_report_gps_pos.vel_e_m_s = 0.0f;
_report_gps_pos.vel_d_m_s = 0.0f;
2015-10-19 13:16:11 +02:00
_report_gps_pos.vel_m_s = sqrtf(_report_gps_pos.vel_n_m_s * _report_gps_pos.vel_n_m_s + _report_gps_pos.vel_e_m_s *
_report_gps_pos.vel_e_m_s + _report_gps_pos.vel_d_m_s * _report_gps_pos.vel_d_m_s);
2015-02-13 14:29:59 +01:00
_report_gps_pos.cog_rad = 0.0f;
2015-10-19 13:16:11 +02:00
_report_gps_pos.vel_ned_valid = true;
2014-01-11 00:46:45 +01:00
/* no time and satellite information simulated */
2014-01-11 00:46:45 +01:00
2015-02-11 17:57:33 +01:00
if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
2014-01-11 00:46:45 +01:00
}
2014-01-11 00:46:45 +01:00
usleep(2e5);
2014-01-11 00:46:45 +01:00
} else {
2014-01-11 00:46:45 +01:00
if (_Helper != nullptr) {
delete(_Helper);
/* set to zero to ensure parser is not used while not instantiated */
_Helper = nullptr;
}
2014-01-11 00:46:45 +01:00
switch (_mode) {
case GPS_DRIVER_MODE_UBX:
_Helper = new UBX(_serial_fd, &_report_gps_pos, _p_report_sat_info);
2014-01-11 00:46:45 +01:00
break;
2014-01-11 00:46:45 +01:00
case GPS_DRIVER_MODE_MTK:
_Helper = new MTK(_serial_fd, &_report_gps_pos);
2014-01-11 00:46:45 +01:00
break;
2014-09-30 15:44:47 +04:00
case GPS_DRIVER_MODE_ASHTECH:
_Helper = new ASHTECH(_serial_fd, &_report_gps_pos, _p_report_sat_info);
break;
2014-01-11 00:46:45 +01:00
default:
break;
}
/* the Ashtech driver lies about successful configuration and the
* MTK driver is not well tested, so we really only trust the UBX
* driver for an advance publication
*/
2014-01-11 00:46:45 +01:00
if (_Helper->configure(_baudrate) == 0) {
/* reset report */
memset(&_report_gps_pos, 0, sizeof(_report_gps_pos));
if (_mode == GPS_DRIVER_MODE_UBX) {
/* Publish initial report that we have access to a GPS,
* but set all critical state fields to indicate we have
* no valid position lock
*/
_report_gps_pos.timestamp_time = hrt_absolute_time();
/* reset the timestamps for data, because we have no data yet */
_report_gps_pos.timestamp_position = 0;
_report_gps_pos.timestamp_variance = 0;
_report_gps_pos.timestamp_velocity = 0;
/* set a massive variance */
_report_gps_pos.eph = 10000.0f;
_report_gps_pos.epv = 10000.0f;
_report_gps_pos.fix_type = 0;
if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
/* GPS is obviously detected successfully, reset statistics */
_Helper->reset_update_rates();
}
int helper_ret;
2015-10-19 13:16:11 +02:00
while ((helper_ret = _Helper->receive(TIMEOUT_5HZ)) > 0 && !_task_should_exit) {
2015-10-19 13:16:11 +02:00
// lock();
2014-01-11 00:46:45 +01:00
/* opportunistic publishing - else invalid data would end up on the bus */
if (helper_ret & 1) {
if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
2016-01-24 15:30:52 +03:00
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
}
2015-10-19 13:16:11 +02:00
if (_p_report_sat_info && (helper_ret & 2)) {
if (_report_sat_info_pub != nullptr) {
orb_publish(ORB_ID(satellite_info), _report_sat_info_pub, _p_report_sat_info);
} else {
_report_sat_info_pub = orb_advertise(ORB_ID(satellite_info), _p_report_sat_info);
}
2014-01-11 00:46:45 +01:00
}
if (helper_ret & 1) { // consider only pos info updates for rate calculation */
last_rate_count++;
}
2014-01-11 00:46:45 +01:00
/* measure update rate every 5 seconds */
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;
_Helper->store_update_rates();
_Helper->reset_update_rates();
}
if (!_healthy) {
2016-03-13 15:40:39 +01:00
// Helpful for debugging, but too verbose for normal ops
2016-03-12 17:14:27 +01:00
// const char *mode_str = "unknown";
//
// switch (_mode) {
// case GPS_DRIVER_MODE_UBX:
// mode_str = "UBX";
// break;
//
// case GPS_DRIVER_MODE_MTK:
// mode_str = "MTK";
// break;
//
// case GPS_DRIVER_MODE_ASHTECH:
// mode_str = "ASHTECH";
// break;
//
// default:
// break;
// }
//
// PX4_WARN("module found: %s", mode_str);
2014-01-11 00:46:45 +01:00
_healthy = true;
}
2014-01-11 00:46:45 +01:00
}
2014-01-11 00:46:45 +01:00
if (_healthy) {
PX4_WARN("module lost");
2014-01-11 00:46:45 +01:00
_healthy = false;
_rate = 0.0f;
}
}
2014-01-11 00:46:45 +01:00
/* select next mode */
switch (_mode) {
case GPS_DRIVER_MODE_UBX:
_mode = GPS_DRIVER_MODE_MTK;
break;
2014-01-11 00:46:45 +01:00
case GPS_DRIVER_MODE_MTK:
2014-10-09 11:15:11 +04:00
_mode = GPS_DRIVER_MODE_ASHTECH;
break;
2014-09-30 15:44:47 +04:00
2014-10-09 11:15:11 +04:00
case GPS_DRIVER_MODE_ASHTECH:
2014-01-11 00:46:45 +01:00
_mode = GPS_DRIVER_MODE_UBX;
break;
2014-01-11 00:46:45 +01:00
default:
break;
}
}
}
PX4_WARN("exiting");
::close(_serial_fd);
/* tell the dtor that we are exiting */
_task = -1;
px4_task_exit(0);
}
void
GPS::cmd_reset()
{
#ifdef GPIO_GPS_NRESET
PX4_WARN("Toggling GPS reset pin");
stm32_configgpio(GPIO_GPS_NRESET);
stm32_gpiowrite(GPIO_GPS_NRESET, 0);
usleep(100);
stm32_gpiowrite(GPIO_GPS_NRESET, 1);
PX4_WARN("Toggled GPS reset pin");
#endif
}
void
GPS::print_info()
{
2015-02-11 17:57:33 +01:00
//GPS Mode
2015-10-19 13:16:11 +02:00
if (_fake_gps) {
PX4_WARN("protocol: SIMULATED");
2015-02-11 17:57:33 +01:00
}
2015-02-11 17:57:33 +01:00
else {
switch (_mode) {
case GPS_DRIVER_MODE_UBX:
PX4_WARN("protocol: UBX");
2015-02-11 17:57:33 +01:00
break;
case GPS_DRIVER_MODE_MTK:
PX4_WARN("protocol: MTK");
2015-02-11 17:57:33 +01:00
break;
2015-10-19 13:16:11 +02:00
case GPS_DRIVER_MODE_ASHTECH:
PX4_WARN("protocol: ASHTECH");
2015-10-19 13:16:11 +02:00
break;
2014-09-30 15:44:47 +04:00
2015-02-11 17:57:33 +01:00
default:
break;
2015-10-19 13:16:11 +02:00
}
2013-02-04 17:55:58 +01:00
}
PX4_WARN("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
PX4_WARN("sat info: %s, noise: %d, jamming detected: %s",
(_p_report_sat_info != nullptr) ? "enabled" : "disabled",
_report_gps_pos.noise_per_ms,
_report_gps_pos.jamming_indicator == 255 ? "YES" : "NO");
if (_report_gps_pos.timestamp_position != 0) {
PX4_WARN("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type,
_report_gps_pos.satellites_used, (double)(hrt_absolute_time() - _report_gps_pos.timestamp_position) / 1000.0);
PX4_WARN("lat: %d, lon: %d, alt: %d", _report_gps_pos.lat, _report_gps_pos.lon, _report_gps_pos.alt);
PX4_WARN("vel: %.2fm/s, %.2fm/s, %.2fm/s", (double)_report_gps_pos.vel_n_m_s,
(double)_report_gps_pos.vel_e_m_s, (double)_report_gps_pos.vel_d_m_s);
PX4_WARN("hdop: %.2f, vdop: %.2f", (double)_report_gps_pos.hdop, (double)_report_gps_pos.vdop);
PX4_WARN("eph: %.2fm, epv: %.2fm", (double)_report_gps_pos.eph, (double)_report_gps_pos.epv);
PX4_WARN("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
PX4_WARN("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
PX4_WARN("rate publication:\t%6.2f Hz", (double)_rate);
2013-02-04 17:55:58 +01:00
}
usleep(100000);
}
/**
* Local functions in support of the shell command.
*/
namespace gps
{
2015-02-11 17:57:33 +01:00
GPS *g_dev = nullptr;
void start(const char *uart_path, bool fake_gps, bool enable_sat_info);
void stop();
void test();
void reset();
void info();
/**
* Start the driver.
*/
void
start(const char *uart_path, bool fake_gps, bool enable_sat_info)
{
2015-10-19 13:16:11 +02:00
if (g_dev != nullptr) {
errx(1, "already started");
2015-10-19 13:16:11 +02:00
}
/* create the driver */
g_dev = new GPS(uart_path, fake_gps, enable_sat_info);
2015-10-19 13:16:11 +02:00
if (g_dev == nullptr) {
goto fail;
2015-10-19 13:16:11 +02:00
}
2015-10-19 13:16:11 +02:00
if (OK != g_dev->init()) {
goto fail;
2015-10-19 13:16:11 +02:00
}
return;
fail:
if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
PX4_ERR("start failed");
return;
}
/**
* Stop the driver.
*/
void
stop()
{
delete g_dev;
g_dev = nullptr;
}
/**
* 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()
{
PX4_ERR("GPS reset not supported");
return;
}
/**
* Print the status of the driver.
*/
void
info()
{
2015-10-19 13:16:11 +02:00
if (g_dev == nullptr) {
PX4_ERR("GPS Not running");
return;
2015-10-19 13:16:11 +02:00
}
g_dev->print_info();
}
} // namespace
int
gps_main(int argc, char *argv[])
{
/* set to default */
const char *device_name = GPS_DEFAULT_UART_PORT;
2014-01-11 00:46:45 +01:00
bool fake_gps = false;
bool enable_sat_info = false;
if (argc < 2) {
goto out;
}
/*
* Start/load the driver.
*/
if (!strcmp(argv[1], "start")) {
/* work around getopt unreliability */
if (argc > 3) {
if (!strcmp(argv[2], "-d")) {
device_name = argv[3];
} else {
PX4_ERR("DID NOT GET -d");
goto out;
}
}
2014-01-11 00:46:45 +01:00
/* Detect fake gps option */
for (int i = 2; i < argc; i++) {
2015-10-19 13:16:11 +02:00
if (!strcmp(argv[i], "-f")) {
2014-01-11 00:46:45 +01:00
fake_gps = true;
2015-10-19 13:16:11 +02:00
}
2014-01-11 00:46:45 +01:00
}
/* Detect sat info option */
for (int i = 2; i < argc; i++) {
2015-10-19 13:16:11 +02:00
if (!strcmp(argv[i], "-s")) {
enable_sat_info = true;
2015-10-19 13:16:11 +02:00
}
}
gps::start(device_name, fake_gps, enable_sat_info);
}
2015-10-19 13:16:11 +02:00
if (!strcmp(argv[1], "stop")) {
gps::stop();
2015-10-19 13:16:11 +02:00
}
/*
* Test the driver/device.
*/
2015-10-19 13:16:11 +02:00
if (!strcmp(argv[1], "test")) {
gps::test();
2015-10-19 13:16:11 +02:00
}
/*
* Reset the driver.
*/
2015-10-19 13:16:11 +02:00
if (!strcmp(argv[1], "reset")) {
gps::reset();
2015-10-19 13:16:11 +02:00
}
/*
* Print driver status.
*/
2015-10-19 13:16:11 +02:00
if (!strcmp(argv[1], "status")) {
gps::info();
2015-10-19 13:16:11 +02:00
}
return 0;
out:
PX4_ERR("unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status'\n [-d /dev/ttyS0-n][-f (for enabling fake)][-s (to enable sat info)]");
return 1;
}