diff --git a/ArduPlane/qautotune.cpp b/ArduPlane/qautotune.cpp index 8ec42c19ee..41c10093a4 100644 --- a/ArduPlane/qautotune.cpp +++ b/ArduPlane/qautotune.cpp @@ -27,7 +27,7 @@ float QAutoTune::get_pilot_desired_climb_rate_cms(void) const return plane.quadplane.get_pilot_desired_climb_rate_cms(); } -void QAutoTune::get_pilot_desired_rp_yrate_cd(int32_t &des_roll_cd, int32_t &des_pitch_cd, int32_t &yaw_rate_cds) +void QAutoTune::get_pilot_desired_rp_yrate_cd(float &des_roll_cd, float &des_pitch_cd, float &yaw_rate_cds) { if (plane.channel_roll->get_control_in() == 0 && plane.channel_pitch->get_control_in() == 0) { des_roll_cd = 0; diff --git a/ArduPlane/qautotune.h b/ArduPlane/qautotune.h index 755c0971e6..5d6bd92a8a 100644 --- a/ArduPlane/qautotune.h +++ b/ArduPlane/qautotune.h @@ -21,7 +21,7 @@ public: protected: float get_pilot_desired_climb_rate_cms(void) const override; - void get_pilot_desired_rp_yrate_cd(int32_t &roll_cd, int32_t &pitch_cd, int32_t &yaw_rate_cds) override; + void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) override; void init_z_limits() override; void Log_Write_Event(enum at_event id) override; void log_pids() override;