mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
ArduPlane: add inflight airspeed cal rc switch
This commit is contained in:
parent
f37d8e5865
commit
3cdcce2123
@ -68,7 +68,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK(one_second_loop, 1, 400),
|
||||
SCHED_TASK(check_long_failsafe, 3, 400),
|
||||
SCHED_TASK(rpm_update, 10, 100),
|
||||
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
SCHED_TASK(airspeed_ratio_update, 1, 100),
|
||||
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
#if HAL_MOUNT_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100),
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
@ -318,6 +320,7 @@ void Plane::efi_update(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
/*
|
||||
once a second update the airspeed calibration ratio
|
||||
*/
|
||||
@ -346,7 +349,7 @@ void Plane::airspeed_ratio_update(void)
|
||||
const Vector3f &vg = gps.velocity();
|
||||
airspeed.update_calibration(vg, aparm.airspeed_max);
|
||||
}
|
||||
|
||||
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
|
||||
/*
|
||||
read the GPS and update position
|
||||
|
@ -967,7 +967,9 @@ private:
|
||||
void afs_fs_check(void);
|
||||
#endif
|
||||
void one_second_loop(void);
|
||||
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
void airspeed_ratio_update(void);
|
||||
#endif
|
||||
void compass_save(void);
|
||||
void update_logging1(void);
|
||||
void update_logging2(void);
|
||||
|
@ -156,6 +156,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
||||
case AUX_FUNC::Q_ASSIST:
|
||||
case AUX_FUNC::SOARING:
|
||||
case AUX_FUNC::AIRMODE:
|
||||
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
case AUX_FUNC::ARSPD_CALIBRATE:
|
||||
#endif
|
||||
do_aux_function(ch_option, ch_flag);
|
||||
break;
|
||||
|
||||
@ -277,6 +280,21 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
||||
}
|
||||
break;
|
||||
|
||||
case AUX_FUNC::ARSPD_CALIBRATE:
|
||||
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
switch (ch_flag) {
|
||||
case AuxSwitchPos::HIGH:
|
||||
plane.airspeed.set_calibration_enabled(true);
|
||||
break;
|
||||
case AuxSwitchPos::MIDDLE:
|
||||
break;
|
||||
case AuxSwitchPos::LOW:
|
||||
plane.airspeed.set_calibration_enabled(false);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AUX_FUNC::LANDING_FLARE:
|
||||
do_aux_function_flare(ch_flag);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user