Browse Source

fixed InertialSensor stub build

master
Andrew Tridgell 13 years ago committed by Pat Hickey
parent
commit
41caa949ca
  1. 4
      ArduCopter/ArduCopter.pde
  2. 2
      libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp

4
ArduCopter/ArduCopter.pde

@ -217,8 +217,8 @@ AP_TimerProcess timer_scheduler; @@ -217,8 +217,8 @@ AP_TimerProcess timer_scheduler;
AP_GPS_HIL g_gps_driver(NULL);
AP_Compass_HIL compass; // never used
AP_IMU_Shim imu; // never used
AP_InertialSensorStub ins;
AP_PeriodicProcessStub timer_scheduler;
AP_InertialSensor_Stub ins;
AP_PeriodicProcessStub timer_scheduler;
#ifdef OPTFLOW_ENABLED
AP_OpticalFlow_ADNS3080 optflow;
#endif

2
libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp

@ -5,7 +5,7 @@ void AP_InertialSensor_Stub::init( AP_PeriodicProcess * scheduler ) {} @@ -5,7 +5,7 @@ void AP_InertialSensor_Stub::init( AP_PeriodicProcess * scheduler ) {}
/*================ AP_INERTIALSENSOR PUBLIC INTERFACE ==================== */
bool AP_InertialSensor_Stub::update( void ) {}
bool AP_InertialSensor_Stub::update( void ) { return true; }
float AP_InertialSensor_Stub::gx() { return 0.0f; }

Loading…
Cancel
Save