mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_GPS: Remove GPS_TC_BLEND
This commit is contained in:
parent
5bd5aa87a7
commit
3edaea9be9
@ -343,7 +343,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
|||||||
// @Units: s
|
// @Units: s
|
||||||
// @Range: 5.0 30.0
|
// @Range: 5.0 30.0
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("_BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f),
|
// Had key 21, no longer used
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Param: _DRV_OPTIONS
|
// @Param: _DRV_OPTIONS
|
||||||
@ -485,11 +485,6 @@ void AP_GPS::init(const AP_SerialManager& serial_manager)
|
|||||||
}
|
}
|
||||||
_last_instance_swap_ms = 0;
|
_last_instance_swap_ms = 0;
|
||||||
|
|
||||||
#if defined(GPS_BLENDED_INSTANCE)
|
|
||||||
// Initialise class variables used to do GPS blending
|
|
||||||
_omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// prep the state instance fields
|
// prep the state instance fields
|
||||||
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
|
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
|
||||||
state[i].instance = i;
|
state[i].instance = i;
|
||||||
|
@ -605,7 +605,6 @@ protected:
|
|||||||
AP_Int16 _delay_ms[GPS_MAX_RECEIVERS];
|
AP_Int16 _delay_ms[GPS_MAX_RECEIVERS];
|
||||||
AP_Int8 _com_port[GPS_MAX_RECEIVERS];
|
AP_Int8 _com_port[GPS_MAX_RECEIVERS];
|
||||||
AP_Int8 _blend_mask;
|
AP_Int8 _blend_mask;
|
||||||
AP_Float _blend_tc;
|
|
||||||
AP_Int16 _driver_options;
|
AP_Int16 _driver_options;
|
||||||
AP_Int8 _primary;
|
AP_Int8 _primary;
|
||||||
#if HAL_ENABLE_DRONECAN_DRIVERS
|
#if HAL_ENABLE_DRONECAN_DRIVERS
|
||||||
@ -739,7 +738,6 @@ private:
|
|||||||
Vector3f _blended_antenna_offset; // blended antenna offset
|
Vector3f _blended_antenna_offset; // blended antenna offset
|
||||||
float _blended_lag_sec; // 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.
|
float _blend_weights[GPS_MAX_RECEIVERS]; // blend weight for each GPS. The blend weights must sum to 1.0 across all instances.
|
||||||
float _omega_lpf; // cutoff frequency in rad/sec of LPF applied to position offsets
|
|
||||||
bool _output_is_blended; // true when a blended GPS solution being output
|
bool _output_is_blended; // true when a blended GPS solution being output
|
||||||
uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy
|
uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user