Browse Source

AP_InertialSensor: add HAL_INS_ENABLED

gps-1.3.1
Siddharth Purohit 4 years ago committed by Andrew Tridgell
parent
commit
c4caf2ff54
  1. 4
      libraries/AP_InertialSensor/AP_InertialSensor.cpp
  2. 3
      libraries/AP_InertialSensor/BatchSampler.cpp

4
libraries/AP_InertialSensor/AP_InertialSensor.cpp

@ -2,6 +2,7 @@ @@ -2,6 +2,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#if HAL_INS_ENABLED
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/SPIDevice.h>
#include <AP_Math/AP_Math.h>
@ -2293,3 +2294,6 @@ AP_InertialSensor &ins() @@ -2293,3 +2294,6 @@ AP_InertialSensor &ins()
}
};
#endif //#if HAL_INS_ENABLED

3
libraries/AP_InertialSensor/BatchSampler.cpp

@ -1,4 +1,6 @@ @@ -1,4 +1,6 @@
#include "AP_InertialSensor.h"
#if HAL_INS_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
@ -276,3 +278,4 @@ void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSenso @@ -276,3 +278,4 @@ void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSenso
data_write_offset++; // may unblock the reading process
}
#endif //#if HAL_INS_ENABLED

Loading…
Cancel
Save