mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
ArduCopter: remove unused g_gps_null pointer to save 2 bytes
This commit is contained in:
parent
085425fdbf
commit
53fc4a9287
@ -282,10 +282,6 @@ AP_InertialSensor_MPU6000 ins;
|
|||||||
AP_InertialSensor_Oilpan ins(&adc);
|
AP_InertialSensor_Oilpan ins(&adc);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// we don't want to use gps for yaw correction on ArduCopter, so pass
|
|
||||||
// a NULL GPS object pointer
|
|
||||||
static GPS *g_gps_null;
|
|
||||||
|
|
||||||
#if DMP_ENABLED == ENABLED && CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
#if DMP_ENABLED == ENABLED && CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||||
AP_AHRS_MPU6000 ahrs(&ins, g_gps); // only works with APM2
|
AP_AHRS_MPU6000 ahrs(&ins, g_gps); // only works with APM2
|
||||||
#else
|
#else
|
||||||
|
Loading…
Reference in New Issue
Block a user