AC_AutoTune: avoid int32_t<->float conversions

We're currently bouncing backwards and forwards between types.  Just
choose one!
This commit is contained in:
Peter Barker 2019-02-28 22:08:39 +11:00 committed by Peter Barker
parent 1859dd4234
commit 247a047177
2 changed files with 8 additions and 8 deletions

View File

@ -356,14 +356,14 @@ void AC_AutoTune::run()
return; return;
} }
int32_t target_roll_cd, target_pitch_cd, target_yaw_rate_cds; float target_roll_cd, target_pitch_cd, target_yaw_rate_cds;
get_pilot_desired_rp_yrate_cd(target_roll_cd, target_pitch_cd, target_yaw_rate_cds); get_pilot_desired_rp_yrate_cd(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);
// get pilot desired climb rate // get pilot desired climb rate
const float target_climb_rate_cms = get_pilot_desired_climb_rate_cms(); const float target_climb_rate_cms = get_pilot_desired_climb_rate_cms();
bool zero_rp_input = target_roll_cd == 0 && target_pitch_cd == 0; const bool zero_rp_input = is_zero(target_roll_cd) && is_zero(target_pitch_cd);
if (!zero_rp_input || target_yaw_rate_cds != 0 || !is_zero(target_climb_rate_cms)) { if (!zero_rp_input || !is_zero(target_yaw_rate_cds) || !is_zero(target_climb_rate_cms)) {
if (!pilot_override) { if (!pilot_override) {
pilot_override = true; pilot_override = true;
// set gains to their original values // set gains to their original values
@ -1618,7 +1618,7 @@ bool AC_AutoTune::position_ok(void)
} }
// get attitude for slow position hold in autotune mode // get attitude for slow position hold in autotune mode
void AC_AutoTune::get_poshold_attitude(int32_t &roll_cd_out, int32_t &pitch_cd_out, int32_t &yaw_cd_out) void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, float &yaw_cd_out)
{ {
roll_cd_out = pitch_cd_out = 0; roll_cd_out = pitch_cd_out = 0;

View File

@ -48,7 +48,7 @@ protected:
virtual float get_pilot_desired_climb_rate_cms(void) const = 0; virtual float get_pilot_desired_climb_rate_cms(void) const = 0;
// get pilot input for designed roll and pitch, and yaw rate // get pilot input for designed roll and pitch, and yaw rate
virtual void get_pilot_desired_rp_yrate_cd(int32_t &roll_cd, int32_t &pitch_cd, int32_t &yaw_rate_cds) = 0; virtual void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) = 0;
// init pos controller Z velocity and accel limits // init pos controller Z velocity and accel limits
virtual void init_z_limits() = 0; virtual void init_z_limits() = 0;
@ -103,7 +103,7 @@ private:
void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max); void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
void updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max); void updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max); void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
void get_poshold_attitude(int32_t &roll_cd, int32_t &pitch_cd, int32_t &yaw_cd); void get_poshold_attitude(float &roll_cd, float &pitch_cd, float &yaw_cd);
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt); void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds); void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
@ -192,7 +192,7 @@ private:
int8_t counter; // counter for tuning gains int8_t counter; // counter for tuning gains
float target_rate, start_rate; // target and start rate float target_rate, start_rate; // target and start rate
float target_angle, start_angle; // target and start angles float target_angle, start_angle; // target and start angles
int32_t desired_yaw_cd; // yaw heading during tune float desired_yaw_cd; // yaw heading during tune
float rate_max, test_accel_max; // maximum acceleration variables float rate_max, test_accel_max; // maximum acceleration variables
float step_scaler; // scaler to reduce maximum target step float step_scaler; // scaler to reduce maximum target step
float abort_angle; // Angle that test is aborted float abort_angle; // Angle that test is aborted
@ -213,7 +213,7 @@ private:
uint32_t announce_time; uint32_t announce_time;
float lean_angle; float lean_angle;
float rotation_rate; float rotation_rate;
int32_t roll_cd, pitch_cd; float roll_cd, pitch_cd;
struct { struct {
LEVEL_ISSUE issue{LEVEL_ISSUE_NONE}; LEVEL_ISSUE issue{LEVEL_ISSUE_NONE};