mirror of https://github.com/ArduPilot/ardupilot
Blimp: moved accel cal update to vehicle code
This commit is contained in:
parent
dbe0bef58b
commit
65c878c06f
|
@ -57,7 +57,6 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_InertialSensor, &blimp.ins, periodic, 400, 50),
|
||||
SCHED_TASK_CLASS(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75),
|
||||
SCHED_TASK_CLASS(Compass, &blimp.compass, cal_update, 100, 100),
|
||||
SCHED_TASK(accel_cal_update, 10, 100),
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Stats, &blimp.g2.stats, update, 1, 100),
|
||||
#endif
|
||||
|
|
|
@ -427,7 +427,6 @@ private:
|
|||
bool rangefinder_up_ok();
|
||||
void rpm_update();
|
||||
void update_optical_flow(void);
|
||||
void accel_cal_update(void);
|
||||
void init_proximity();
|
||||
void update_proximity();
|
||||
|
||||
|
|
|
@ -7,23 +7,3 @@ void Blimp::read_barometer(void)
|
|||
|
||||
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
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue