mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_GPS: Remove stuff from headers
This commit is contained in:
parent
d65f4b5ff8
commit
52eb832883
@ -20,6 +20,7 @@
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_RTC/AP_RTC.h>
|
||||
#include <climits>
|
||||
|
||||
#include "AP_GPS_NOVA.h"
|
||||
@ -42,6 +43,10 @@
|
||||
#include "AP_GPS_UAVCAN.h"
|
||||
#endif
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
#define GPS_RTK_INJECT_TO_ALL 127
|
||||
#define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
|
||||
#define GPS_BAUD_TIME_MS 1200
|
||||
#define GPS_TIMEOUT_MS 4000u
|
||||
|
||||
@ -1103,7 +1108,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages()
|
||||
bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
|
||||
{
|
||||
// always enusre a lag is provided
|
||||
lag_sec = GPS_WORST_LAG_SEC;
|
||||
lag_sec = 0.22f;
|
||||
|
||||
if (instance >= GPS_MAX_INSTANCES) {
|
||||
return false;
|
||||
@ -1541,7 +1546,9 @@ bool AP_GPS::is_healthy(uint8_t instance) const
|
||||
return false;
|
||||
}
|
||||
|
||||
bool last_msg_valid = last_message_delta_time_ms(instance) < GPS_MAX_DELTA_MS;
|
||||
const uint16_t gps_max_delta_ms = 245; // 200 ms (5Hz) + 45 ms buffer
|
||||
|
||||
bool last_msg_valid = last_message_delta_time_ms(instance) < gps_max_delta_ms;
|
||||
|
||||
if (instance == GPS_BLENDED_INSTANCE) {
|
||||
return last_msg_valid && blend_health_check();
|
||||
|
@ -19,11 +19,8 @@
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include "GPS_detect_state.h"
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_RTC/AP_RTC.h>
|
||||
|
||||
/**
|
||||
maximum number of GPS instances available on this platform. If more
|
||||
@ -32,11 +29,7 @@
|
||||
#define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data
|
||||
#define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPS instances including the 'virtual' GPS created by blending receiver data
|
||||
#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)
|
||||
#define GPS_RTK_INJECT_TO_ALL 127
|
||||
#define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
|
||||
#define GPS_UNKNOWN_DOP UINT16_MAX // set unknown DOP's to maximum value, which is also correct for MAVLink
|
||||
#define GPS_WORST_LAG_SEC 0.22f // worst lag value any GPS driver is expected to return, expressed in seconds
|
||||
#define GPS_MAX_DELTA_MS 245 // 200 ms (5Hz) + 45 ms buffer
|
||||
|
||||
// the number of GPS leap seconds
|
||||
#define GPS_LEAPSECONDS_MILLIS 18000ULL
|
||||
@ -545,7 +538,7 @@ private:
|
||||
Vector2f _NE_pos_offset_m[GPS_MAX_RECEIVERS]; // Filtered North,East position offset from GPS instance to blended solution in _output_state.location (m)
|
||||
float _hgt_offset_cm[GPS_MAX_RECEIVERS]; // Filtered height offset from GPS instance relative to blended solution in _output_state.location (cm)
|
||||
Vector3f _blended_antenna_offset; // blended antenna offset
|
||||
float _blended_lag_sec = 0.001f * GPS_MAX_RATE_MS; // blended receiver lag in seconds
|
||||
float _blended_lag_sec; // blended receiver lag in seconds
|
||||
float _blend_weights[GPS_MAX_RECEIVERS]; // blend weight for each GPS. The blend weights must sum to 1.0 across all instances.
|
||||
uint32_t _last_time_updated[GPS_MAX_RECEIVERS]; // the last value of state.last_gps_time_ms read for that GPS instance - used to detect new data.
|
||||
float _omega_lpf; // cutoff frequency in rad/sec of LPF applied to position offsets
|
||||
|
@ -15,6 +15,7 @@
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
#define GPS_BACKEND_DEBUGGING 0
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user