mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 16:08:28 -04:00
4251ee0e4b
The ublox driver will now continuosly poll for the settings from the GPS and correct any that are found to be in correct. This status is then reported to the arming library as an additional arming check, allowing the user to be sure that the gps is correctly configured before using it. If a user has a GPS2 configured that is not present they will fail the arming checks until after they have disabled the second GPS. 2 new parameters were introduced as well: -GPS_AUTO_CONFIG: Will not request any configuration packets to attempt to change them. (If the packet is recieved then a update will be sent to it, but in testing this scenario never occured. This is set to 1 or 0 to change the setting. (Defaults to 1 enabling auto config) -GPS_GNSS_MODE2: Behaves the same way as GPS_GNSS_MODE but only applies to the second GPS. GPS drivers are now allowed 2 seconds of non responsiveness before being unloaded
75 lines
2.5 KiB
C++
75 lines
2.5 KiB
C++
// -*- 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/>.
|
|
*/
|
|
|
|
/*
|
|
GPS driver backend class
|
|
*/
|
|
#ifndef __AP_GPS_BACKEND_H__
|
|
#define __AP_GPS_BACKEND_H__
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
#include "AP_GPS.h"
|
|
|
|
class AP_GPS_Backend
|
|
{
|
|
public:
|
|
AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
|
|
|
// we declare a virtual destructor so that GPS drivers can
|
|
// override with a custom destructor if need be.
|
|
virtual ~AP_GPS_Backend(void) {}
|
|
|
|
// The read() method is the only one needed in each driver. It
|
|
// should return true when the backend has successfully received a
|
|
// valid packet from the GPS.
|
|
virtual bool read() = 0;
|
|
|
|
// Highest status supported by this GPS.
|
|
// Allows external system to identify type of receiver connected.
|
|
virtual AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D; }
|
|
|
|
virtual bool is_configured(void) { return true; }
|
|
|
|
virtual void inject_data(uint8_t *data, uint8_t len) { return; }
|
|
|
|
//MAVLink methods
|
|
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan) { return ; }
|
|
|
|
virtual void send_mavlink_gps2_rtk(mavlink_channel_t chan) { return ; }
|
|
|
|
protected:
|
|
AP_HAL::UARTDriver *port; ///< UART we are attached to
|
|
AP_GPS &gps; ///< access to frontend (for parameters)
|
|
AP_GPS::GPS_State &state; ///< public state for this instance
|
|
|
|
// common utility functions
|
|
int32_t swap_int32(int32_t v) const;
|
|
int16_t swap_int16(int16_t v) const;
|
|
|
|
/*
|
|
fill in 3D velocity from 2D components
|
|
*/
|
|
void fill_3d_velocity(void);
|
|
|
|
/*
|
|
fill in time_week_ms and time_week from BCD date and time components
|
|
assumes MTK19 millisecond form of bcd_time
|
|
*/
|
|
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
|
|
};
|
|
|
|
#endif // __AP_GPS_BACKEND_H__
|