AC_AttitudeControl: Heli: remove unused flags

This commit is contained in:
Iampete1 2023-07-19 14:13:22 +01:00 committed by Randy Mackay
parent d927af03e9
commit 6ece7ffb2e
2 changed files with 5 additions and 31 deletions

View File

@ -403,19 +403,9 @@ void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_r
float roll_out = roll_pid + roll_ff;
float pitch_out = pitch_pid + pitch_ff;
// constrain output and update limit flags
if (fabsf(roll_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
_flags_heli.limit_roll = true;
} else {
_flags_heli.limit_roll = false;
}
if (fabsf(pitch_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
_flags_heli.limit_pitch = true;
} else {
_flags_heli.limit_pitch = false;
}
// constrain output
roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
// output to motors
_motors.set_roll(roll_out);
@ -457,13 +447,8 @@ float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_ra
// add feed forward
float yaw_out = pid + vff;
// constrain output and update limit flag
if (fabsf(yaw_out) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX) {
yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX);
_flags_heli.limit_yaw = true;
} else {
_flags_heli.limit_yaw = false;
}
// constrain output
yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX);
// output to motors
return yaw_out;

View File

@ -42,13 +42,9 @@ public:
AP_Param::setup_object_defaults(this, var_info);
// initialise flags
_flags_heli.limit_roll = false;
_flags_heli.limit_pitch = false;
_flags_heli.limit_yaw = false;
_flags_heli.leaky_i = true;
_flags_heli.flybar_passthrough = false;
_flags_heli.tail_passthrough = false;
_flags_heli.do_piro_comp = false;
}
// pid accessors
@ -82,9 +78,6 @@ public:
_flags_heli.tail_passthrough = tail_passthrough;
}
// do_piro_comp - controls whether piro-comp is active or not
void do_piro_comp(bool piro_comp) { _flags_heli.do_piro_comp = piro_comp; }
// set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition.
void set_hover_roll_trim_scalar(float scalar) override {_hover_roll_trim_scalar = constrain_float(scalar, 0.0f, 1.0f);}
@ -112,13 +105,9 @@ private:
// To-Do: move these limits flags into the heli motors class
struct AttControlHeliFlags {
uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move
uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move
uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move
uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage
uint8_t flybar_passthrough : 1; // 1 if we should pass through pilots roll & pitch input directly to swash-plate
uint8_t tail_passthrough : 1; // 1 if we should pass through pilots yaw input to tail
uint8_t do_piro_comp : 1; // 1 if we should do pirouette compensation on roll/pitch
} _flags_heli;
//