2014-03-28 16:52:27 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
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/>.
*/
2015-08-11 03:28:43 -03:00
# include <AP_Common/AP_Common.h>
# include <AP_Math/AP_Math.h>
# include <AP_HAL/AP_HAL.h>
# include <AP_Notify/AP_Notify.h>
# include "AP_GPS.h"
2014-03-28 16:52:27 -03:00
extern const AP_HAL : : HAL & hal ;
// table of user settable parameters
const AP_Param : : GroupInfo AP_GPS : : var_info [ ] PROGMEM = {
// @Param: TYPE
// @DisplayName: GPS type
// @Description: GPS type
2015-04-23 08:16:21 -03:00
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:PX4-UAVCAN
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2014-03-28 16:52:27 -03:00
AP_GROUPINFO ( " TYPE " , 0 , AP_GPS , _type [ 0 ] , 1 ) ,
2014-04-03 20:08:28 -03:00
# if GPS_MAX_INSTANCES > 1
2014-06-06 18:58:11 -03:00
2014-03-28 16:52:27 -03:00
// @Param: TYPE2
// @DisplayName: 2nd GPS type
// @Description: GPS type of 2nd GPS
2015-04-23 08:16:21 -03:00
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:PX4-UAVCAN
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2014-03-28 16:52:27 -03:00
AP_GROUPINFO ( " TYPE2 " , 1 , AP_GPS , _type [ 1 ] , 0 ) ,
2014-06-06 18:58:11 -03:00
2014-04-03 20:08:28 -03:00
# endif
2014-03-28 16:52:27 -03:00
// @Param: NAVFILTER
// @DisplayName: Navigation filter setting
// @Description: Navigation filter engine setting
2014-05-20 10:08:40 -03:00
// @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2014-03-28 16:52:27 -03:00
AP_GROUPINFO ( " NAVFILTER " , 2 , AP_GPS , _navfilter , GPS_ENGINE_AIRBORNE_4G ) ,
2014-06-06 18:58:11 -03:00
# if GPS_MAX_INSTANCES > 1
// @Param: AUTO_SWITCH
// @DisplayName: Automatic Switchover Setting
// @Description: Automatic switchover to GPS reporting best lock
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO ( " AUTO_SWITCH " , 3 , AP_GPS , _auto_switch , 1 ) ,
# endif
# if GPS_RTK_AVAILABLE
2015-07-21 07:50:12 -03:00
// @Param: MIN_DGPS
2014-06-06 18:58:11 -03:00
// @DisplayName: Minimum Lock Type Accepted for DGPS
// @Description: Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
// @Values: 0:Any,50:FloatRTK,100:IntegerRTK
// @User: Advanced
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2014-06-06 18:58:11 -03:00
AP_GROUPINFO ( " MIN_DGPS " , 4 , AP_GPS , _min_dgps , 100 ) ,
# endif
2014-09-04 01:27:05 -03:00
// @Param: SBAS_MODE
// @DisplayName: SBAS Mode
// @Description: This sets the SBAS (satellite based augmentation system) mode if available on this GPS. If set to 2 then the SBAS mode is not changed in the GPS. Otherwise the GPS will be reconfigured to enable/disable SBAS. Disabling SBAS may be worthwhile in some parts of the world where an SBAS signal is available but the baseline is too long to be useful.
// @Values: 0:Disabled,1:Enabled,2:NoChange
// @User: Advanced
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2014-09-04 01:27:05 -03:00
AP_GROUPINFO ( " SBAS_MODE " , 5 , AP_GPS , _sbas_mode , 2 ) ,
2014-09-04 01:43:29 -03:00
// @Param: MIN_ELEV
// @DisplayName: Minimum elevation
// @Description: This sets the minimum elevation of satellites above the horizon for them to be used for navigation. Setting this to -100 leaves the minimum elevation set to the GPS modules default.
// @Range: -100 90
// @Units: Degrees
// @User: Advanced
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2014-09-04 01:43:29 -03:00
AP_GROUPINFO ( " MIN_ELEV " , 6 , AP_GPS , _min_elevation , - 100 ) ,
2015-04-22 20:10:46 -03:00
# if GPS_MAX_INSTANCES > 1
// @Param: INJECT_TO
// @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets
// @Description: The GGS can send raw serial packets to inject data to multiple GPSes.
2015-06-27 04:26:25 -03:00
// @Values: 0:send to first GPS, 1:send to 2nd GPS, 127:send to all
AP_GROUPINFO ( " INJECT_TO " , 7 , AP_GPS , _inject_to , GPS_RTK_INJECT_TO_ALL ) ,
2015-04-22 20:10:46 -03:00
# endif
# if GPS_RTK_AVAILABLE
// @Param: SBP_LOGMASK
// @DisplayName: Swift Binary Protocol Logging Mask
// @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
2015-06-27 04:26:25 -03:00
// @Values: 0x0000:None, 0xFFFF:All, 0xFF00:External only
2015-04-22 20:10:46 -03:00
// @User: Advanced
AP_GROUPINFO ( " SBP_LOGMASK " , 8 , AP_GPS , _sbp_logmask , 0xFF00 ) ,
# endif
2015-05-04 05:18:34 -03:00
# if GPS_RTK_AVAILABLE
2015-07-21 07:50:12 -03:00
// @Param: RAW_DATA
2015-05-04 05:18:34 -03:00
// @DisplayName: Raw data logging
// @Description: Enable logging of RXM raw data from uBlox which includes carrier phase and pseudo range information. This allows for post processing of dataflash logs for more precise positioning. Note that this requires a raw capable uBlox such as the 6P or 6T.
2015-07-21 07:50:12 -03:00
// @Values: 0:Disabled,1:log at 1MHz,5:log at 5MHz
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2015-05-04 05:18:34 -03:00
AP_GROUPINFO ( " RAW_DATA " , 9 , AP_GPS , _raw_data , 0 ) ,
# endif
2015-07-14 18:12:47 -03:00
// @Param: GNSS_MODE
// @DisplayName: GNSS system configuration
2015-09-01 00:19:59 -03:00
// @Description: Bitmask for what GNSS system to use (all unchecked or zero to leave GPS as configured)
2015-09-09 01:38:51 -03:00
// @Values: 0:Leave as currently configured, 1:GPS-NoSBAS, 3:GPS+SBAS, 4:Galileo-NoSBAS, 6:Galileo+SBAS, 8:Beidou, 51:GPS+IMES+QZSS+SBAS (Japan Only), 64:GLONASS, 66:GLONASS+SBAS, 67:GPS+GLONASS+SBAS
2015-09-01 00:19:59 -03:00
// @Bitmask: 0:GPS, 1:SBAS, 2:Galileo, 3:Beidou, 4:IMES, 5:QZSS, 6:GLOSNASS
2015-07-14 18:12:47 -03:00
// @User: Advanced
2015-07-24 02:32:21 -03:00
// @RebootRequired: True
2015-07-14 18:12:47 -03:00
AP_GROUPINFO ( " GNSS_MODE " , 10 , AP_GPS , _gnss_mode , 0 ) ,
2014-03-28 16:52:27 -03:00
AP_GROUPEND
} ;
/// Startup initialisation.
2015-01-19 09:36:35 -04:00
void AP_GPS : : init ( DataFlash_Class * dataflash , const AP_SerialManager & serial_manager )
2014-03-28 16:52:27 -03:00
{
_DataFlash = dataflash ;
2014-06-06 18:58:11 -03:00
primary_instance = 0 ;
2015-01-19 09:36:35 -04:00
// search for serial ports with gps protocol
2015-03-27 22:46:32 -03:00
_port [ 0 ] = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_GPS , 0 ) ;
2015-01-29 00:37:08 -04:00
2014-10-29 00:02:59 -03:00
# if GPS_MAX_INSTANCES > 1
2015-03-27 22:46:32 -03:00
_port [ 1 ] = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_GPS , 1 ) ;
2015-05-21 18:07:59 -03:00
_last_instance_swap_ms = 0 ;
2014-04-03 20:08:28 -03:00
# endif
2014-03-28 16:52:27 -03:00
}
// baudrates to try to detect GPSes with
2015-06-30 11:09:00 -03:00
const uint32_t AP_GPS : : _baudrates [ ] PROGMEM = { 4800U , 38400U , 115200U , 57600U , 9600U , 230400U } ;
2014-03-28 16:52:27 -03:00
// initialisation blobs to send to the GPS to try to get it into the
// right mode
2015-09-02 06:13:38 -03:00
const prog_char AP_GPS : : _initialisation_blob [ ] PROGMEM = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY ;
2015-07-14 15:45:09 -03:00
const prog_char AP_GPS : : _initialisation_raw_blob [ ] PROGMEM = UBLOX_SET_BINARY_RAW_BAUD MTK_SET_BINARY SIRF_SET_BINARY ;
2014-03-28 16:52:27 -03:00
2014-03-31 06:48:22 -03:00
/*
send some more initialisation string bytes if there is room in the
UART transmit buffer
*/
void AP_GPS : : send_blob_start ( uint8_t instance , const prog_char * _blob , uint16_t size )
{
initblob_state [ instance ] . blob = _blob ;
initblob_state [ instance ] . remaining = size ;
}
/*
send some more initialisation string bytes if there is room in the
UART transmit buffer
*/
void AP_GPS : : send_blob_update ( uint8_t instance )
{
2015-01-19 09:36:35 -04:00
// exit immediately if no uart for this instance
if ( _port [ instance ] = = NULL ) {
return ;
}
2014-03-31 06:48:22 -03:00
// see if we can write some more of the initialisation blob
if ( initblob_state [ instance ] . remaining > 0 ) {
2015-01-19 09:36:35 -04:00
int16_t space = _port [ instance ] - > txspace ( ) ;
2014-03-31 06:48:22 -03:00
if ( space > ( int16_t ) initblob_state [ instance ] . remaining ) {
space = initblob_state [ instance ] . remaining ;
}
while ( space > 0 ) {
2015-01-19 09:36:35 -04:00
_port [ instance ] - > write ( pgm_read_byte ( initblob_state [ instance ] . blob ) ) ;
2014-03-31 06:48:22 -03:00
initblob_state [ instance ] . blob + + ;
space - - ;
initblob_state [ instance ] . remaining - - ;
}
}
}
2014-03-28 16:52:27 -03:00
/*
run detection step for one GPS instance . If this finds a GPS then it
will fill in drivers [ instance ] and change state [ instance ] . status
from NO_GPS to NO_FIX .
*/
void
AP_GPS : : detect_instance ( uint8_t instance )
{
AP_GPS_Backend * new_gps = NULL ;
struct detect_state * dstate = & detect_state [ instance ] ;
2014-11-13 23:44:15 -04:00
uint32_t now = hal . scheduler - > millis ( ) ;
2014-03-28 16:52:27 -03:00
2014-11-13 23:44:15 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
2014-11-03 08:37:06 -04:00
if ( _type [ instance ] = = GPS_TYPE_PX4 ) {
// check for explicitely chosen PX4 GPS beforehand
// it is not possible to autodetect it, nor does it require a real UART
hal . console - > print_P ( PSTR ( " PX4 " ) ) ;
2015-01-19 09:36:35 -04:00
new_gps = new AP_GPS_PX4 ( * this , state [ instance ] , _port [ instance ] ) ;
2014-11-13 23:44:15 -04:00
goto found_gps ;
2014-11-03 08:37:06 -04:00
}
2014-11-13 23:44:15 -04:00
# endif
2015-01-19 09:36:35 -04:00
if ( _port [ instance ] = = NULL ) {
2014-03-28 16:52:27 -03:00
// UART not available
return ;
}
2014-03-31 08:13:55 -03:00
state [ instance ] . instance = instance ;
state [ instance ] . status = NO_GPS ;
2015-08-04 03:45:47 -03:00
state [ instance ] . hdop = 9999 ;
2014-03-31 08:13:55 -03:00
2015-09-03 19:41:29 -03:00
# if GPS_RTK_AVAILABLE
// by default the sbf gps outputs no data on its port, until configured.
if ( _type [ instance ] = = GPS_TYPE_SBF ) {
hal . console - > print_P ( PSTR ( " SBF " ) ) ;
new_gps = new AP_GPS_SBF ( * this , state [ instance ] , _port [ instance ] ) ;
}
# endif // GPS_RTK_AVAILABLE
2014-03-28 16:52:27 -03:00
// record the time when we started detection. This is used to try
// to avoid initialising a uBlox as a NMEA GPS
if ( dstate - > detect_started_ms = = 0 ) {
dstate - > detect_started_ms = now ;
}
2015-07-14 04:07:29 -03:00
if ( now - dstate - > last_baud_change_ms > GPS_BAUD_TIME_MS ) {
2014-03-28 16:52:27 -03:00
// try the next baud rate
dstate - > last_baud + + ;
2015-07-20 16:53:46 -03:00
if ( dstate - > last_baud = = ARRAY_SIZE ( _baudrates ) ) {
2014-03-28 16:52:27 -03:00
dstate - > last_baud = 0 ;
}
2014-04-04 20:05:54 -03:00
uint32_t baudrate = pgm_read_dword ( & _baudrates [ dstate - > last_baud ] ) ;
2015-01-26 09:21:08 -04:00
_port [ instance ] - > begin ( baudrate ) ;
2015-01-29 00:53:20 -04:00
_port [ instance ] - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
2014-03-28 16:52:27 -03:00
dstate - > last_baud_change_ms = now ;
2015-07-14 15:45:09 -03:00
# if UBLOX_RXM_RAW_LOGGING
if ( _raw_data ! = 0 )
send_blob_start ( instance , _initialisation_raw_blob , sizeof ( _initialisation_raw_blob ) ) ;
else
# endif
2014-03-31 06:48:22 -03:00
send_blob_start ( instance , _initialisation_blob , sizeof ( _initialisation_blob ) ) ;
2014-03-28 16:52:27 -03:00
}
2014-03-31 06:48:22 -03:00
send_blob_update ( instance ) ;
2014-03-28 16:52:27 -03:00
2015-07-14 04:07:29 -03:00
while ( initblob_state [ instance ] . remaining = = 0 & & _port [ instance ] - > available ( ) > 0
& & new_gps = = NULL ) {
2015-01-19 09:36:35 -04:00
uint8_t data = _port [ instance ] - > read ( ) ;
2014-03-28 16:52:27 -03:00
/*
running a uBlox at less than 38400 will lead to packet
corruption , as we can ' t receive the packets in the 200 ms
window for 5 Hz fixes . The NMEA startup message should force
the uBlox into 38400 no matter what rate it is configured
for .
*/
if ( ( _type [ instance ] = = GPS_TYPE_AUTO | | _type [ instance ] = = GPS_TYPE_UBLOX ) & &
2014-04-04 20:05:54 -03:00
pgm_read_dword ( & _baudrates [ dstate - > last_baud ] ) > = 38400 & &
2014-03-28 16:52:27 -03:00
AP_GPS_UBLOX : : _detect ( dstate - > ublox_detect_state , data ) ) {
hal . console - > print_P ( PSTR ( " ublox " ) ) ;
2015-01-19 09:36:35 -04:00
new_gps = new AP_GPS_UBLOX ( * this , state [ instance ] , _port [ instance ] ) ;
2014-03-28 16:52:27 -03:00
}
else if ( ( _type [ instance ] = = GPS_TYPE_AUTO | | _type [ instance ] = = GPS_TYPE_MTK19 ) & &
AP_GPS_MTK19 : : _detect ( dstate - > mtk19_detect_state , data ) ) {
hal . console - > print_P ( PSTR ( " MTK19 " ) ) ;
2015-01-19 09:36:35 -04:00
new_gps = new AP_GPS_MTK19 ( * this , state [ instance ] , _port [ instance ] ) ;
2014-03-28 16:52:27 -03:00
}
else if ( ( _type [ instance ] = = GPS_TYPE_AUTO | | _type [ instance ] = = GPS_TYPE_MTK ) & &
AP_GPS_MTK : : _detect ( dstate - > mtk_detect_state , data ) ) {
hal . console - > print_P ( PSTR ( " MTK " ) ) ;
2015-01-19 09:36:35 -04:00
new_gps = new AP_GPS_MTK ( * this , state [ instance ] , _port [ instance ] ) ;
2014-03-28 16:52:27 -03:00
}
2014-06-06 18:58:11 -03:00
# if GPS_RTK_AVAILABLE
2014-04-04 20:05:54 -03:00
else if ( ( _type [ instance ] = = GPS_TYPE_AUTO | | _type [ instance ] = = GPS_TYPE_SBP ) & &
AP_GPS_SBP : : _detect ( dstate - > sbp_detect_state , data ) ) {
hal . console - > print_P ( PSTR ( " SBP " ) ) ;
2015-01-19 09:36:35 -04:00
new_gps = new AP_GPS_SBP ( * this , state [ instance ] , _port [ instance ] ) ;
2014-04-04 20:05:54 -03:00
}
2014-04-05 07:39:55 -03:00
# endif // HAL_CPU_CLASS
2014-07-13 03:40:53 -03:00
# if !defined(GPS_SKIP_SIRF_NMEA)
2014-03-28 16:52:27 -03:00
// save a bit of code space on a 1280
else if ( ( _type [ instance ] = = GPS_TYPE_AUTO | | _type [ instance ] = = GPS_TYPE_SIRF ) & &
AP_GPS_SIRF : : _detect ( dstate - > sirf_detect_state , data ) ) {
hal . console - > print_P ( PSTR ( " SIRF " ) ) ;
2015-01-19 09:36:35 -04:00
new_gps = new AP_GPS_SIRF ( * this , state [ instance ] , _port [ instance ] ) ;
2014-03-28 16:52:27 -03:00
}
2015-07-14 04:07:29 -03:00
else if ( now - dstate - > detect_started_ms > ( ARRAY_SIZE ( _baudrates ) * GPS_BAUD_TIME_MS ) ) {
2014-03-28 16:52:27 -03:00
// prevent false detection of NMEA mode in
// a MTK or UBLOX which has booted in NMEA mode
if ( ( _type [ instance ] = = GPS_TYPE_AUTO | | _type [ instance ] = = GPS_TYPE_NMEA ) & &
AP_GPS_NMEA : : _detect ( dstate - > nmea_detect_state , data ) ) {
hal . console - > print_P ( PSTR ( " NMEA " ) ) ;
2015-01-19 09:36:35 -04:00
new_gps = new AP_GPS_NMEA ( * this , state [ instance ] , _port [ instance ] ) ;
2014-03-28 16:52:27 -03:00
}
}
# endif
}
2015-02-05 02:29:25 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
2014-11-13 23:44:15 -04:00
found_gps :
2015-02-05 02:29:25 -04:00
# endif
2014-03-28 16:52:27 -03:00
if ( new_gps ! = NULL ) {
state [ instance ] . status = NO_FIX ;
2014-03-31 08:13:55 -03:00
drivers [ instance ] = new_gps ;
timing [ instance ] . last_message_time_ms = now ;
2014-03-28 16:52:27 -03:00
}
}
2014-06-06 18:58:11 -03:00
AP_GPS : : GPS_Status
AP_GPS : : highest_supported_status ( uint8_t instance ) const
{
# if GPS_RTK_AVAILABLE
if ( drivers [ instance ] ! = NULL )
return drivers [ instance ] - > highest_supported_status ( ) ;
# endif
return AP_GPS : : GPS_OK_FIX_3D ;
}
AP_GPS : : GPS_Status
AP_GPS : : highest_supported_status ( void ) const
{
# if GPS_RTK_AVAILABLE
if ( drivers [ primary_instance ] ! = NULL )
return drivers [ primary_instance ] - > highest_supported_status ( ) ;
# endif
return AP_GPS : : GPS_OK_FIX_3D ;
}
2014-03-28 16:52:27 -03:00
/*
2014-03-31 06:48:22 -03:00
update one GPS instance . This should be called at 10 Hz or greater
2014-03-28 16:52:27 -03:00
*/
void
AP_GPS : : update_instance ( uint8_t instance )
{
2014-04-01 03:25:15 -03:00
if ( _type [ instance ] = = GPS_TYPE_HIL ) {
// in HIL, leave info alone
return ;
}
2014-03-28 16:52:27 -03:00
if ( _type [ instance ] = = GPS_TYPE_NONE ) {
// not enabled
state [ instance ] . status = NO_GPS ;
2015-08-04 03:45:47 -03:00
state [ instance ] . hdop = 9999 ;
2014-03-28 16:52:27 -03:00
return ;
}
2014-04-04 17:33:34 -03:00
if ( locked_ports & ( 1U < < instance ) ) {
// the port is locked by another driver
return ;
}
2014-03-28 16:52:27 -03:00
if ( drivers [ instance ] = = NULL | | state [ instance ] . status = = NO_GPS ) {
// we don't yet know the GPS type of this one, or it has timed
// out and needs to be re-initialised
detect_instance ( instance ) ;
return ;
}
2014-03-31 06:48:22 -03:00
send_blob_update ( instance ) ;
2014-03-28 16:52:27 -03:00
// we have an active driver for this instance
bool result = drivers [ instance ] - > read ( ) ;
uint32_t tnow = hal . scheduler - > millis ( ) ;
// if we did not get a message, and the idle timer of 1.2 seconds
// has expired, re-initialise the GPS. This will cause GPS
// detection to run again
if ( ! result ) {
if ( tnow - timing [ instance ] . last_message_time_ms > 1200 ) {
2014-03-31 16:11:55 -03:00
// free the driver before we run the next detection, so we
// don't end up with two allocated at any time
delete drivers [ instance ] ;
drivers [ instance ] = NULL ;
2014-04-01 17:48:36 -03:00
memset ( & state [ instance ] , 0 , sizeof ( state [ instance ] ) ) ;
state [ instance ] . instance = instance ;
state [ instance ] . status = NO_GPS ;
2015-08-04 03:45:47 -03:00
state [ instance ] . hdop = 9999 ;
2014-04-01 17:48:36 -03:00
timing [ instance ] . last_message_time_ms = tnow ;
2014-03-28 16:52:27 -03:00
}
} else {
timing [ instance ] . last_message_time_ms = tnow ;
if ( state [ instance ] . status > = GPS_OK_FIX_2D ) {
timing [ instance ] . last_fix_time_ms = tnow ;
}
}
}
/*
update all GPS instances
*/
void
AP_GPS : : update ( void )
{
for ( uint8_t i = 0 ; i < GPS_MAX_INSTANCES ; i + + ) {
update_instance ( i ) ;
}
2014-03-31 16:14:19 -03:00
2014-04-03 20:08:28 -03:00
# if GPS_MAX_INSTANCES > 1
2014-04-03 18:32:34 -03:00
// work out which GPS is the primary, and how many sensors we have
for ( uint8_t i = 0 ; i < GPS_MAX_INSTANCES ; i + + ) {
if ( state [ i ] . status ! = NO_GPS ) {
num_instances = i + 1 ;
}
2014-06-06 18:58:11 -03:00
if ( _auto_switch ) {
if ( i = = primary_instance ) {
continue ;
}
if ( state [ i ] . status > state [ primary_instance ] . status ) {
// we have a higher status lock, change GPS
primary_instance = i ;
continue ;
}
2015-05-21 18:07:59 -03:00
bool another_gps_has_1_or_more_sats = ( state [ i ] . num_sats > = state [ primary_instance ] . num_sats + 1 ) ;
if ( state [ i ] . status = = state [ primary_instance ] . status & & another_gps_has_1_or_more_sats ) {
uint32_t now = hal . scheduler - > millis ( ) ;
bool another_gps_has_2_or_more_sats = ( state [ i ] . num_sats > = state [ primary_instance ] . num_sats + 2 ) ;
if ( ( another_gps_has_1_or_more_sats & & ( now - _last_instance_swap_ms ) > = 20000 ) | |
( another_gps_has_2_or_more_sats & & ( now - _last_instance_swap_ms ) > = 5000 ) ) {
// this GPS has more satellites than the
2014-06-06 18:58:11 -03:00
// current primary, switch primary. Once we switch we will
// then tend to stick to the new GPS as primary. We don't
// want to switch too often as it will look like a
// position shift to the controllers.
primary_instance = i ;
2015-05-21 18:07:59 -03:00
_last_instance_swap_ms = now ;
}
2014-06-06 18:58:11 -03:00
}
} else {
primary_instance = 0 ;
2014-04-03 18:32:34 -03:00
}
}
2014-04-11 08:32:55 -03:00
# else
num_instances = 1 ;
2014-04-03 20:08:28 -03:00
# endif // GPS_MAX_INSTANCES
2014-09-21 09:48:35 -03:00
// update notify with gps status. We always base this on the primary_instance
AP_Notify : : flags . gps_status = state [ primary_instance ] . status ;
2014-03-28 16:52:27 -03:00
}
2014-03-31 06:48:22 -03:00
/*
set HIL ( hardware in the loop ) status for a GPS instance
*/
2014-03-28 16:52:27 -03:00
void
2014-04-01 17:49:29 -03:00
AP_GPS : : setHIL ( uint8_t instance , GPS_Status _status , uint64_t time_epoch_ms ,
2014-08-09 09:47:54 -03:00
const Location & _location , const Vector3f & _velocity , uint8_t _num_sats ,
2014-04-01 17:49:29 -03:00
uint16_t hdop , bool _have_vertical_velocity )
2014-03-28 16:52:27 -03:00
{
2014-04-01 17:49:29 -03:00
if ( instance > = GPS_MAX_INSTANCES ) {
return ;
}
2014-03-28 16:52:27 -03:00
uint32_t tnow = hal . scheduler - > millis ( ) ;
2014-04-01 17:49:29 -03:00
GPS_State & istate = state [ instance ] ;
2014-03-28 16:52:27 -03:00
istate . status = _status ;
istate . location = _location ;
istate . location . options = 0 ;
istate . velocity = _velocity ;
istate . ground_speed = pythagorous2 ( istate . velocity . x , istate . velocity . y ) ;
2015-08-30 19:24:35 -03:00
istate . ground_course_cd = wrap_360_cd ( degrees ( atan2f ( istate . velocity . y , istate . velocity . x ) ) * 100UL ) ;
2014-04-01 17:49:29 -03:00
istate . hdop = hdop ;
2014-03-28 16:52:27 -03:00
istate . num_sats = _num_sats ;
2015-06-16 02:48:10 -03:00
istate . have_vertical_velocity | = _have_vertical_velocity ;
2014-03-28 16:52:27 -03:00
istate . last_gps_time_ms = tnow ;
2014-09-03 17:37:42 -03:00
uint64_t gps_time_ms = time_epoch_ms - ( 17000ULL * 86400ULL + 52 * 10 * 7000ULL * 86400ULL - 15000ULL ) ;
istate . time_week = gps_time_ms / ( 86400 * 7 * ( uint64_t ) 1000 ) ;
istate . time_week_ms = gps_time_ms - istate . time_week * ( 86400 * 7 * ( uint64_t ) 1000 ) ;
2014-04-01 17:49:29 -03:00
timing [ instance ] . last_message_time_ms = tnow ;
timing [ instance ] . last_fix_time_ms = tnow ;
_type [ instance ] . set ( GPS_TYPE_HIL ) ;
2014-03-28 16:52:27 -03:00
}
2014-04-04 17:33:34 -03:00
/**
Lock a GPS port , prevening the GPS driver from using it . This can
be used to allow a user to control a GPS port via the
SERIAL_CONTROL protocol
*/
void
AP_GPS : : lock_port ( uint8_t instance , bool lock )
{
2015-04-22 20:10:46 -03:00
2014-04-04 17:33:34 -03:00
if ( instance > = GPS_MAX_INSTANCES ) {
return ;
}
if ( lock ) {
locked_ports | = ( 1U < < instance ) ;
} else {
locked_ports & = ~ ( 1U < < instance ) ;
}
}
2014-06-06 18:58:11 -03:00
2015-04-22 20:10:46 -03:00
//Inject a packet of raw binary to a GPS
void
AP_GPS : : inject_data ( uint8_t * data , uint8_t len )
{
# if GPS_MAX_INSTANCES > 1
//Support broadcasting to all GPSes.
2015-06-27 04:26:25 -03:00
if ( _inject_to = = GPS_RTK_INJECT_TO_ALL ) {
2015-04-22 20:10:46 -03:00
for ( uint8_t i = 0 ; i < GPS_MAX_INSTANCES ; i + + ) {
inject_data ( i , data , len ) ;
}
} else {
inject_data ( _inject_to , data , len ) ;
}
# else
inject_data ( 0 , data , len ) ;
# endif
}
void
AP_GPS : : inject_data ( uint8_t instance , uint8_t * data , uint8_t len )
{
if ( instance < GPS_MAX_INSTANCES & & drivers [ instance ] ! = NULL )
drivers [ instance ] - > inject_data ( data , len ) ;
}
2014-06-06 18:58:11 -03:00
void
AP_GPS : : send_mavlink_gps_raw ( mavlink_channel_t chan )
{
2015-04-23 19:21:00 -03:00
static uint32_t last_send_time_ms [ MAVLINK_COMM_NUM_BUFFERS ] ;
2015-01-02 02:08:11 -04:00
if ( status ( 0 ) > AP_GPS : : NO_GPS ) {
// when we have a GPS then only send new data
2015-04-23 19:21:00 -03:00
if ( last_send_time_ms [ chan ] = = last_message_time_ms ( 0 ) ) {
2015-01-02 02:08:11 -04:00
return ;
}
2015-04-23 19:21:00 -03:00
last_send_time_ms [ chan ] = last_message_time_ms ( 0 ) ;
2015-01-02 02:08:11 -04:00
} else {
// when we don't have a GPS then send at 1Hz
uint32_t now = hal . scheduler - > millis ( ) ;
2015-04-23 19:21:00 -03:00
if ( now - last_send_time_ms [ chan ] < 1000 ) {
2015-01-02 02:08:11 -04:00
return ;
}
2015-04-23 19:21:00 -03:00
last_send_time_ms [ chan ] = now ;
2014-06-06 18:58:11 -03:00
}
2015-01-02 02:08:11 -04:00
const Location & loc = location ( 0 ) ;
mavlink_msg_gps_raw_int_send (
chan ,
last_fix_time_ms ( 0 ) * ( uint64_t ) 1000 ,
status ( 0 ) ,
loc . lat , // in 1E7 degrees
loc . lng , // in 1E7 degrees
loc . alt * 10UL , // in mm
get_hdop ( 0 ) ,
2015-09-07 19:37:13 -03:00
get_vdop ( 0 ) ,
2015-01-02 02:08:11 -04:00
ground_speed ( 0 ) * 100 , // cm/s
ground_course_cd ( 0 ) , // 1/100 degrees,
num_sats ( 0 ) ) ;
2014-06-06 18:58:11 -03:00
}
# if GPS_MAX_INSTANCES > 1
void
AP_GPS : : send_mavlink_gps2_raw ( mavlink_channel_t chan )
{
2015-04-23 19:21:00 -03:00
static uint32_t last_send_time_ms [ MAVLINK_COMM_NUM_BUFFERS ] ;
2015-01-02 02:08:11 -04:00
if ( num_sensors ( ) < 2 | | status ( 1 ) < = AP_GPS : : NO_GPS ) {
return ;
}
// when we have a GPS then only send new data
2015-04-23 19:21:00 -03:00
if ( last_send_time_ms [ chan ] = = last_message_time_ms ( 1 ) ) {
2015-01-02 02:08:11 -04:00
return ;
2014-06-06 18:58:11 -03:00
}
2015-04-23 19:21:00 -03:00
last_send_time_ms [ chan ] = last_message_time_ms ( 1 ) ;
2015-01-02 02:08:11 -04:00
const Location & loc = location ( 1 ) ;
mavlink_msg_gps2_raw_send (
chan ,
last_fix_time_ms ( 1 ) * ( uint64_t ) 1000 ,
status ( 1 ) ,
loc . lat ,
loc . lng ,
loc . alt * 10UL ,
get_hdop ( 1 ) ,
2015-09-07 19:37:13 -03:00
get_vdop ( 1 ) ,
2015-01-02 02:08:11 -04:00
ground_speed ( 1 ) * 100 , // cm/s
ground_course_cd ( 1 ) , // 1/100 degrees,
num_sats ( 1 ) ,
0 ,
0 ) ;
2014-06-06 18:58:11 -03:00
}
# endif
# if GPS_RTK_AVAILABLE
void
AP_GPS : : send_mavlink_gps_rtk ( mavlink_channel_t chan )
{
if ( drivers [ 0 ] ! = NULL & & drivers [ 0 ] - > highest_supported_status ( ) > AP_GPS : : GPS_OK_FIX_3D ) {
drivers [ 0 ] - > send_mavlink_gps_rtk ( chan ) ;
}
}
# if GPS_MAX_INSTANCES > 1
void
AP_GPS : : send_mavlink_gps2_rtk ( mavlink_channel_t chan )
{
if ( drivers [ 1 ] ! = NULL & & drivers [ 1 ] - > highest_supported_status ( ) > AP_GPS : : GPS_OK_FIX_3D ) {
drivers [ 1 ] - > send_mavlink_gps_rtk ( chan ) ;
}
}
# endif
# endif