ArduCopter: rename pid setters to include set_ in the names

This commit is contained in:
Peter Barker 2024-07-30 21:37:51 +10:00 committed by Andrew Tridgell
parent 90ee339806
commit 5f40319a3b
1 changed files with 29 additions and 29 deletions

View File

@ -37,70 +37,70 @@ void Copter::tuning()
// Roll, Pitch tuning
case TUNING_STABILIZE_ROLL_PITCH_KP:
attitude_control->get_angle_roll_p().kP(tuning_value);
attitude_control->get_angle_pitch_p().kP(tuning_value);
attitude_control->get_angle_roll_p().set_kP(tuning_value);
attitude_control->get_angle_pitch_p().set_kP(tuning_value);
break;
case TUNING_RATE_ROLL_PITCH_KP:
attitude_control->get_rate_roll_pid().kP(tuning_value);
attitude_control->get_rate_pitch_pid().kP(tuning_value);
attitude_control->get_rate_roll_pid().set_kP(tuning_value);
attitude_control->get_rate_pitch_pid().set_kP(tuning_value);
break;
case TUNING_RATE_ROLL_PITCH_KI:
attitude_control->get_rate_roll_pid().kI(tuning_value);
attitude_control->get_rate_pitch_pid().kI(tuning_value);
attitude_control->get_rate_roll_pid().set_kI(tuning_value);
attitude_control->get_rate_pitch_pid().set_kI(tuning_value);
break;
case TUNING_RATE_ROLL_PITCH_KD:
attitude_control->get_rate_roll_pid().kD(tuning_value);
attitude_control->get_rate_pitch_pid().kD(tuning_value);
attitude_control->get_rate_roll_pid().set_kD(tuning_value);
attitude_control->get_rate_pitch_pid().set_kD(tuning_value);
break;
// Yaw tuning
case TUNING_STABILIZE_YAW_KP:
attitude_control->get_angle_yaw_p().kP(tuning_value);
attitude_control->get_angle_yaw_p().set_kP(tuning_value);
break;
case TUNING_YAW_RATE_KP:
attitude_control->get_rate_yaw_pid().kP(tuning_value);
attitude_control->get_rate_yaw_pid().set_kP(tuning_value);
break;
case TUNING_YAW_RATE_KD:
attitude_control->get_rate_yaw_pid().kD(tuning_value);
attitude_control->get_rate_yaw_pid().set_kD(tuning_value);
break;
// Altitude and throttle tuning
case TUNING_ALTITUDE_HOLD_KP:
pos_control->get_pos_z_p().kP(tuning_value);
pos_control->get_pos_z_p().set_kP(tuning_value);
break;
case TUNING_THROTTLE_RATE_KP:
pos_control->get_vel_z_pid().kP(tuning_value);
pos_control->get_vel_z_pid().set_kP(tuning_value);
break;
case TUNING_ACCEL_Z_KP:
pos_control->get_accel_z_pid().kP(tuning_value);
pos_control->get_accel_z_pid().set_kP(tuning_value);
break;
case TUNING_ACCEL_Z_KI:
pos_control->get_accel_z_pid().kI(tuning_value);
pos_control->get_accel_z_pid().set_kI(tuning_value);
break;
case TUNING_ACCEL_Z_KD:
pos_control->get_accel_z_pid().kD(tuning_value);
pos_control->get_accel_z_pid().set_kD(tuning_value);
break;
// Loiter and navigation tuning
case TUNING_LOITER_POSITION_KP:
pos_control->get_pos_xy_p().kP(tuning_value);
pos_control->get_pos_xy_p().set_kP(tuning_value);
break;
case TUNING_VEL_XY_KP:
pos_control->get_vel_xy_pid().kP(tuning_value);
pos_control->get_vel_xy_pid().set_kP(tuning_value);
break;
case TUNING_VEL_XY_KI:
pos_control->get_vel_xy_pid().kI(tuning_value);
pos_control->get_vel_xy_pid().set_kI(tuning_value);
break;
case TUNING_WP_SPEED:
@ -127,15 +127,15 @@ void Copter::tuning()
break;
case TUNING_RATE_PITCH_FF:
attitude_control->get_rate_pitch_pid().ff(tuning_value);
attitude_control->get_rate_pitch_pid().set_ff(tuning_value);
break;
case TUNING_RATE_ROLL_FF:
attitude_control->get_rate_roll_pid().ff(tuning_value);
attitude_control->get_rate_roll_pid().set_ff(tuning_value);
break;
case TUNING_RATE_YAW_FF:
attitude_control->get_rate_yaw_pid().ff(tuning_value);
attitude_control->get_rate_yaw_pid().set_ff(tuning_value);
break;
#endif
@ -154,27 +154,27 @@ void Copter::tuning()
break;
case TUNING_RATE_PITCH_KP:
attitude_control->get_rate_pitch_pid().kP(tuning_value);
attitude_control->get_rate_pitch_pid().set_kP(tuning_value);
break;
case TUNING_RATE_PITCH_KI:
attitude_control->get_rate_pitch_pid().kI(tuning_value);
attitude_control->get_rate_pitch_pid().set_kI(tuning_value);
break;
case TUNING_RATE_PITCH_KD:
attitude_control->get_rate_pitch_pid().kD(tuning_value);
attitude_control->get_rate_pitch_pid().set_kD(tuning_value);
break;
case TUNING_RATE_ROLL_KP:
attitude_control->get_rate_roll_pid().kP(tuning_value);
attitude_control->get_rate_roll_pid().set_kP(tuning_value);
break;
case TUNING_RATE_ROLL_KI:
attitude_control->get_rate_roll_pid().kI(tuning_value);
attitude_control->get_rate_roll_pid().set_kI(tuning_value);
break;
case TUNING_RATE_ROLL_KD:
attitude_control->get_rate_roll_pid().kD(tuning_value);
attitude_control->get_rate_roll_pid().set_kD(tuning_value);
break;
#if FRAME_CONFIG != HELI_FRAME
@ -184,7 +184,7 @@ void Copter::tuning()
#endif
case TUNING_RATE_YAW_FILT:
attitude_control->get_rate_yaw_pid().filt_E_hz(tuning_value);
attitude_control->get_rate_yaw_pid().set_filt_E_hz(tuning_value);
break;
case TUNING_SYSTEM_ID_MAGNITUDE: