diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 6636571d3c..d466e545ff 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -81,7 +81,7 @@ public: void set_accel_roll_max(float accel_roll_max) { _accel_roll_max = accel_roll_max; } // Sets and saves the roll acceleration limit in centidegrees/s/s - void save_accel_roll_max(float accel_roll_max) { _accel_roll_max = accel_roll_max; _accel_roll_max.save(); } + void save_accel_roll_max(float accel_roll_max) { _accel_roll_max.set_and_save(accel_roll_max); } // Sets the pitch acceleration limit in centidegrees/s/s float get_accel_pitch_max() { return _accel_pitch_max; } @@ -90,7 +90,7 @@ public: void set_accel_pitch_max(float accel_pitch_max) { _accel_pitch_max = accel_pitch_max; } // Sets and saves the pitch acceleration limit in centidegrees/s/s - void save_accel_pitch_max(float accel_pitch_max) { _accel_pitch_max = accel_pitch_max; _accel_pitch_max.save(); } + void save_accel_pitch_max(float accel_pitch_max) { _accel_pitch_max.set_and_save(accel_pitch_max); } // Gets the yaw acceleration limit in centidegrees/s/s float get_accel_yaw_max() { return _accel_yaw_max; } @@ -99,7 +99,7 @@ public: void set_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max = accel_yaw_max; } // Sets and saves the yaw acceleration limit in centidegrees/s/s - void save_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max = accel_yaw_max; _accel_yaw_max.save(); } + void save_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max.set_and_save(accel_yaw_max); } // Ensure attitude controller have zero errors to relax rate controller output void relax_attitude_controllers();