#include "Blimp.h" // return barometric altitude in centimeters void Blimp::read_barometer(void) { barometer.update(); baro_alt = barometer.get_altitude() * 100.0f; } void Blimp::accel_cal_update() { if (hal.util->get_soft_armed()) { return; } ins.acal_update(); // check if new trim values, and set them float trim_roll, trim_pitch; if (ins.get_new_trim(trim_roll, trim_pitch)) { ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); } #ifdef CAL_ALWAYS_REBOOT if (ins.accel_cal_requires_reboot()) { hal.scheduler->delay(1000); hal.scheduler->reboot(false); } #endif }