APM: fixed hil build
This commit is contained in:
parent
d27e51f20a
commit
034fb5b194
@ -1,10 +1,5 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// Sensors are not available in HIL_MODE_ATTITUDE
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
|
||||
void ReadSCP1000(void) {}
|
||||
|
||||
static void init_barometer(void)
|
||||
{
|
||||
barometer.calibrate(mavlink_delay);
|
||||
@ -37,8 +32,6 @@ static void zero_airspeed(void)
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("zero airspeed calibrated"));
|
||||
}
|
||||
|
||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||
|
||||
static void read_battery(void)
|
||||
{
|
||||
if(g.battery_monitoring == 0) {
|
||||
|
@ -16,6 +16,10 @@ bool AP_Baro_BMP085_HIL::init(AP_PeriodicProcess * scheduler)
|
||||
return true;
|
||||
}
|
||||
|
||||
void AP_Baro_BMP085_HIL::calibrate(void (*callback)(unsigned long t))
|
||||
{
|
||||
// nothing to do
|
||||
}
|
||||
|
||||
// Read the sensor. This is a state machine
|
||||
// We read one time Temperature (state = 1) and then 4 times Pressure (states 2-5)
|
||||
|
@ -25,6 +25,7 @@ public:
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
void setHIL(float Temp, float Press);
|
||||
void calibrate(void (*callback)(unsigned long t));
|
||||
};
|
||||
|
||||
#endif // __AP_BARO_BMP085_HIL_H__
|
||||
|
Loading…
Reference in New Issue
Block a user