2018-12-07 03:52:05 -04:00
|
|
|
/*
|
|
|
|
support for autotune of quadplanes
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
#define QAUTOTUNE_ENABLED !HAL_MINIMIZE_FEATURES
|
|
|
|
|
|
|
|
#if QAUTOTUNE_ENABLED
|
|
|
|
|
|
|
|
#include <AC_AutoTune/AC_AutoTune.h>
|
|
|
|
|
|
|
|
class QAutoTune : public AC_AutoTune
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
friend class QuadPlane;
|
|
|
|
|
|
|
|
bool init() override;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
float get_pilot_desired_climb_rate_cms(void) const override;
|
2019-02-28 07:11:05 -04:00
|
|
|
void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) override;
|
2018-12-07 03:52:05 -04:00
|
|
|
void init_z_limits() override;
|
2018-12-21 22:26:31 -04:00
|
|
|
void log_pids() override;
|
2018-12-07 03:52:05 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // QAUTOTUNE_ENABLED
|