mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: add stick gesture to begin compass calibration
This commit is contained in:
parent
36b5d43efb
commit
a393bd26d7
@ -259,6 +259,13 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef COMPASS_CAL_STICK_GESTURE_TIME
|
||||
#define COMPASS_CAL_STICK_GESTURE_TIME 2.0f // 2 seconds
|
||||
#endif
|
||||
#ifndef COMPASS_CAL_STICK_DELAY
|
||||
#define COMPASS_CAL_STICK_DELAY 5.0f
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// OPTICAL_FLOW
|
||||
#ifndef OPTFLOW
|
||||
|
@ -188,15 +188,34 @@ void Copter::read_receiver_rssi(void)
|
||||
|
||||
void Copter::compass_cal_update()
|
||||
{
|
||||
static uint32_t compass_cal_stick_gesture_begin = 0;
|
||||
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
compass.compass_cal_update();
|
||||
}
|
||||
|
||||
#ifdef CAL_ALWAYS_REBOOT
|
||||
if (compass.compass_cal_requires_reboot()) {
|
||||
hal.scheduler->delay(1000);
|
||||
hal.scheduler->reboot(false);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (compass.is_calibrating()) {
|
||||
if (channel_yaw->get_control_in() < -4000 && channel_throttle->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_throttle->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) {
|
||||
compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,false);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Copter::accel_cal_update()
|
||||
|
Loading…
Reference in New Issue
Block a user