2014-11-03 08:36:14 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
// GPS proxy driver for APM on PX4 platforms
|
|
|
|
//
|
|
|
|
// This driver subscribes on PX4s vehicle_gps_position topic and presents the data received to APM.
|
|
|
|
// The publisher could be an UAVCAN GNSS module like http://docs.zubax.com/Zubax_GNSS, or any other GNSS
|
|
|
|
// hardware supported by the PX4 ecosystem.
|
|
|
|
//
|
|
|
|
// Code by Holger Steinhaus
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-11-13 23:44:15 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
2014-11-03 08:36:14 -04:00
|
|
|
#include "AP_GPS_PX4.h"
|
2014-11-13 23:44:15 -04:00
|
|
|
|
2014-11-03 08:36:14 -04:00
|
|
|
#include <uORB/uORB.h>
|
|
|
|
|
2016-03-31 18:43:36 -03:00
|
|
|
#include <cmath>
|
2014-11-03 08:36:14 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
AP_GPS_PX4::AP_GPS_PX4(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
|
|
|
AP_GPS_Backend(_gps, _state, _port)
|
|
|
|
{
|
|
|
|
_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-06-09 12:31:26 -03:00
|
|
|
const uint64_t MS_PER_WEEK = ((uint64_t)7)*24*3600*1000;
|
|
|
|
const uint64_t DELTA_POSIX_GPS_EPOCH = ((uint64_t)3657)*24*3600*1000;
|
|
|
|
const uint64_t LEAP_MS_GPS_2016 = ((uint64_t)17)*1000;
|
2014-11-03 08:36:14 -04:00
|
|
|
|
|
|
|
// update internal state if new GPS information is available
|
|
|
|
bool
|
|
|
|
AP_GPS_PX4::read(void)
|
|
|
|
{
|
|
|
|
bool updated = false;
|
|
|
|
orb_check(_gps_sub, &updated);
|
|
|
|
|
|
|
|
if (updated) {
|
|
|
|
if (OK == orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &_gps_pos)) {
|
2015-11-19 23:10:22 -04:00
|
|
|
state.last_gps_time_ms = AP_HAL::millis();
|
2014-11-03 08:36:14 -04:00
|
|
|
state.status = (AP_GPS::GPS_Status) (_gps_pos.fix_type | AP_GPS::NO_FIX);
|
|
|
|
state.num_sats = _gps_pos.satellites_used;
|
|
|
|
state.hdop = uint16_t(_gps_pos.eph*100.0f + .5f);
|
|
|
|
|
2014-11-28 08:26:51 -04:00
|
|
|
if (_gps_pos.fix_type >= 2) {
|
|
|
|
state.location.lat = _gps_pos.lat;
|
|
|
|
state.location.lng = _gps_pos.lon;
|
|
|
|
state.location.alt = _gps_pos.alt/10;
|
|
|
|
|
|
|
|
state.ground_speed = _gps_pos.vel_m_s;
|
2016-05-04 22:28:35 -03:00
|
|
|
state.ground_course = wrap_360(degrees(_gps_pos.cog_rad));
|
2015-08-21 07:59:53 -03:00
|
|
|
state.hdop = _gps_pos.eph*100;
|
2014-11-28 08:26:51 -04:00
|
|
|
|
|
|
|
// convert epoch timestamp back to gps epoch - evil hack until we get the genuine
|
|
|
|
// raw week information (or APM switches to Posix epoch ;-) )
|
2016-06-09 12:31:26 -03:00
|
|
|
uint64_t epoch_ms = _gps_pos.time_utc_usec/1000;
|
|
|
|
uint64_t gps_ms = epoch_ms - DELTA_POSIX_GPS_EPOCH + LEAP_MS_GPS_2016;
|
|
|
|
state.time_week = (uint16_t)(gps_ms / MS_PER_WEEK);
|
|
|
|
state.time_week_ms = (uint32_t)(gps_ms - (state.time_week)*MS_PER_WEEK);
|
2014-11-28 08:27:49 -04:00
|
|
|
|
2015-01-05 17:36:15 -04:00
|
|
|
if (_gps_pos.time_utc_usec == 0) {
|
2014-11-28 08:27:49 -04:00
|
|
|
// This is a work-around for https://github.com/PX4/Firmware/issues/1474
|
2016-05-12 14:02:29 -03:00
|
|
|
// reject position reports with invalid time, as APM adjusts it's clock after the first lock has been acquired
|
2014-11-28 08:27:49 -04:00
|
|
|
state.status = AP_GPS::NO_FIX;
|
|
|
|
}
|
2014-11-28 08:26:51 -04:00
|
|
|
}
|
|
|
|
if (_gps_pos.fix_type >= 3) {
|
|
|
|
state.have_vertical_velocity = _gps_pos.vel_ned_valid;
|
|
|
|
state.velocity.x = _gps_pos.vel_n_m_s;
|
|
|
|
state.velocity.y = _gps_pos.vel_e_m_s;
|
|
|
|
state.velocity.z = _gps_pos.vel_d_m_s;
|
2015-08-21 07:59:53 -03:00
|
|
|
state.speed_accuracy = _gps_pos.s_variance_m_s;
|
|
|
|
state.have_speed_accuracy = true;
|
2014-11-28 08:26:51 -04:00
|
|
|
}
|
|
|
|
else {
|
|
|
|
state.have_vertical_velocity = false;
|
|
|
|
}
|
2014-11-03 08:36:14 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return updated;
|
2014-11-13 23:44:15 -04:00
|
|
|
}
|
|
|
|
#endif
|