mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Blimp: remove stick gesture compass cal start and stop
This commit is contained in:
parent
0895cf0a07
commit
ee5ff413a9
@ -56,7 +56,7 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = {
|
|||||||
#endif
|
#endif
|
||||||
SCHED_TASK_CLASS(AP_InertialSensor, &blimp.ins, periodic, 400, 50),
|
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(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75),
|
||||||
SCHED_TASK(compass_cal_update, 100, 100),
|
SCHED_TASK_CLASS(Compass, &blimp.compass, cal_update, 100, 100),
|
||||||
SCHED_TASK(accel_cal_update, 10, 100),
|
SCHED_TASK(accel_cal_update, 10, 100),
|
||||||
#if STATS_ENABLED == ENABLED
|
#if STATS_ENABLED == ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Stats, &blimp.g2.stats, update, 1, 100),
|
SCHED_TASK_CLASS(AP_Stats, &blimp.g2.stats, update, 1, 100),
|
||||||
|
@ -429,7 +429,6 @@ private:
|
|||||||
bool rangefinder_up_ok();
|
bool rangefinder_up_ok();
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
void update_optical_flow(void);
|
void update_optical_flow(void);
|
||||||
void compass_cal_update(void);
|
|
||||||
void accel_cal_update(void);
|
void accel_cal_update(void);
|
||||||
void init_proximity();
|
void init_proximity();
|
||||||
void update_proximity();
|
void update_proximity();
|
||||||
|
@ -8,37 +8,6 @@ void Blimp::read_barometer(void)
|
|||||||
baro_alt = barometer.get_altitude() * 100.0f;
|
baro_alt = barometer.get_altitude() * 100.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void Blimp::compass_cal_update()
|
|
||||||
{
|
|
||||||
compass.cal_update();
|
|
||||||
|
|
||||||
if (hal.util->get_soft_armed()) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint32_t compass_cal_stick_gesture_begin = 0;
|
|
||||||
|
|
||||||
if (compass.is_calibrating()) {
|
|
||||||
if (channel_yaw->get_control_in() < -4000 && channel_down->get_control_in() > 900) {
|
|
||||||
compass.cancel_calibration_all();
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
bool stick_gesture_detected = compass_cal_stick_gesture_begin != 0 && !motors->armed() && channel_yaw->get_control_in() > 4000 && channel_down->get_control_in() > 900;
|
|
||||||
uint32_t tnow = millis();
|
|
||||||
|
|
||||||
if (!stick_gesture_detected) {
|
|
||||||
compass_cal_stick_gesture_begin = tnow;
|
|
||||||
} else if (tnow-compass_cal_stick_gesture_begin > 1000*COMPASS_CAL_STICK_GESTURE_TIME) {
|
|
||||||
#ifdef CAL_ALWAYS_REBOOT
|
|
||||||
compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,true);
|
|
||||||
#else
|
|
||||||
compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,false);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void Blimp::accel_cal_update()
|
void Blimp::accel_cal_update()
|
||||||
{
|
{
|
||||||
if (hal.util->get_soft_armed()) {
|
if (hal.util->get_soft_armed()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user