From e2bbc795ad7bd97ac58ae5f81adaaa57df42d060 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 25 Feb 2012 15:08:42 +1100 Subject: [PATCH] ACM: use a NULL gps pointer in DCM init current DCM API does need a GPS reference passed in, but it can be NULL --- ArduCopter/ArduCopter.pde | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 2a1684062b..e37b3a16d4 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -220,8 +220,10 @@ AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN ); AP_InertialSensor_Oilpan ins(&adc); #endif AP_IMU_INS imu(&ins); -// we don't want to use gps for yaw correction on ArduCopter -AP_DCM dcm(&imu, NULL); +// we don't want to use gps for yaw correction on ArduCopter, so pass +// a NULL GPS object pointer +static GPS *g_gps_null; +AP_DCM dcm(&imu, g_gps_null); AP_TimerProcess timer_scheduler; #elif HIL_MODE == HIL_MODE_SENSORS