Browse Source

ACM: use a NULL gps pointer in DCM init

current DCM API does need a GPS reference passed in, but it can be
NULL
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
e2bbc795ad
  1. 6
      ArduCopter/ArduCopter.pde

6
ArduCopter/ArduCopter.pde

@ -220,8 +220,10 @@ AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN ); @@ -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

Loading…
Cancel
Save