Copter: don't pass channel_yaw->norm_input_dz() into get_pilot_desired_yaw_rate

This commit is contained in:
Iampete1 2024-09-19 23:33:02 +01:00 committed by Randy Mackay
parent cb1a156987
commit a72182ae97
15 changed files with 19 additions and 16 deletions

View File

@ -314,7 +314,7 @@ AC_AttitudeControl::HeadingCommand Mode::AutoYaw::get_heading()
_pilot_yaw_rate_cds = 0.0;
if (!copter.failsafe.radio && copter.flightmode->use_pilot_yaw()) {
// get pilot's desired yaw rate
_pilot_yaw_rate_cds = copter.flightmode->get_pilot_desired_yaw_rate(copter.channel_yaw->norm_input_dz());
_pilot_yaw_rate_cds = copter.flightmode->get_pilot_desired_yaw_rate();
if (!is_zero(_pilot_yaw_rate_cds)) {
auto_yaw.set_mode(AutoYaw::Mode::PILOT_RATE);
}

View File

@ -1035,13 +1035,16 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms)
// transform pilot's yaw input into a desired yaw rate
// returns desired yaw rate in centi-degrees per second
float Mode::get_pilot_desired_yaw_rate(float yaw_in)
float Mode::get_pilot_desired_yaw_rate() const
{
// throttle failsafe check
if (copter.failsafe.radio || !rc().has_ever_seen_rc_input()) {
return 0.0f;
}
// Get yaw input
const float yaw_in = channel_yaw->norm_input_dz();
// convert pilot input to the desired yaw rate
return g2.command_model_pilot.get_rate() * 100.0 * input_expo(yaw_in, g2.command_model_pilot.get_expo());
}

View File

@ -163,7 +163,7 @@ public:
// pilot input processing
void get_pilot_desired_lean_angles(float &roll_out_cd, float &pitch_out_cd, float angle_max_cd, float angle_limit_cd) const;
Vector2f get_pilot_desired_velocity(float vel_max) const;
float get_pilot_desired_yaw_rate(float yaw_in);
float get_pilot_desired_yaw_rate() const;
float get_pilot_desired_throttle() const;
// returns climb target_rate reduced to avoid obstacles and

View File

@ -111,7 +111,7 @@ void ModeAcro_Heli::run()
// if there is no external gyro then run the usual
// ACRO_YAW_P gain on the input control, including
// deadzone
yaw_in = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
yaw_in = get_pilot_desired_yaw_rate();
}
// run attitude controller

View File

@ -36,7 +36,7 @@ void ModeAltHold::run()
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max_cd());
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
float target_yaw_rate = get_pilot_desired_yaw_rate();
// get pilot desired climb rate
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());

View File

@ -282,7 +282,7 @@ void ModeAutorotate::run()
get_pilot_desired_lean_angles(pilot_roll, pilot_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
// Get pilot's desired yaw rate
float pilot_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
float pilot_yaw_rate = get_pilot_desired_yaw_rate();
// Pitch target is calculated in autorotation phase switch above
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pilot_roll, _pitch_target, pilot_yaw_rate);

View File

@ -75,7 +75,7 @@ void AutoTune::get_pilot_desired_rp_yrate_cd(float &des_roll_cd, float &des_pitc
{
copter.mode_autotune.get_pilot_desired_lean_angles(des_roll_cd, des_pitch_cd, copter.aparm.angle_max,
copter.attitude_control->get_althold_lean_angle_max_cd());
yaw_rate_cds = copter.mode_autotune.get_pilot_desired_yaw_rate(copter.channel_yaw->norm_input_dz());
yaw_rate_cds = copter.mode_autotune.get_pilot_desired_yaw_rate();
}
/*

View File

@ -248,7 +248,7 @@ void ModeFlowHold::run()
target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), copter.g.pilot_speed_up);
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(copter.channel_yaw->norm_input_dz());
float target_yaw_rate = get_pilot_desired_yaw_rate();
// Flow Hold State Machine Determination
AltHoldModeState flowhold_state = get_alt_hold_state(target_climb_rate);

View File

@ -102,7 +102,7 @@ void ModeLoiter::run()
loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
target_yaw_rate = get_pilot_desired_yaw_rate();
// get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());

View File

@ -83,7 +83,7 @@ void ModePosHold::run()
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max_cd());
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
float target_yaw_rate = get_pilot_desired_yaw_rate();
// get pilot desired climb rate (for alt-hold mode and take-off)
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());

View File

@ -62,7 +62,7 @@ void ModeSport::run()
}
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
float target_yaw_rate = get_pilot_desired_yaw_rate();
// get pilot desired climb rate
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());

View File

@ -16,7 +16,7 @@ void ModeStabilize::run()
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
float target_yaw_rate = get_pilot_desired_yaw_rate();
if (!motors->armed()) {
// Motors should be Stopped

View File

@ -31,7 +31,7 @@ void ModeStabilize_Heli::run()
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
float target_yaw_rate = get_pilot_desired_yaw_rate();
// get pilot's desired throttle
pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());

View File

@ -176,7 +176,7 @@ void ModeSystemId::run()
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
target_yaw_rate = get_pilot_desired_yaw_rate();
if (!motors->armed()) {
// Motors should be Stopped

View File

@ -264,7 +264,7 @@ void ModeZigZag::auto_control()
float target_yaw_rate = 0;
if (!copter.failsafe.radio) {
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
target_yaw_rate = get_pilot_desired_yaw_rate();
}
// set motors to full range
@ -305,7 +305,7 @@ void ModeZigZag::manual_control()
// process pilot's roll and pitch input
loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
target_yaw_rate = get_pilot_desired_yaw_rate();
// get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());