From ac94ba33ffb5236a33afa1c33e39080ec5a08df9 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Jul 2022 04:08:57 +0100 Subject: [PATCH] ArduCopter: params always use set method --- ArduCopter/Attitude.cpp | 2 +- ArduCopter/RC_Channel.cpp | 6 +++--- ArduCopter/compassmot.cpp | 2 +- ArduCopter/mode.h | 2 +- ArduCopter/mode_turtle.cpp | 6 +++--- ArduCopter/motor_test.cpp | 6 +++--- 6 files changed, 12 insertions(+), 12 deletions(-) diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index 5d4660c51d..e797a52d58 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -58,7 +58,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control) throttle_control = constrain_float(throttle_control,0.0f,1000.0f); // ensure a reasonable deadzone - g.throttle_deadzone = constrain_int16(g.throttle_deadzone, 0, 400); + g.throttle_deadzone.set(constrain_int16(g.throttle_deadzone, 0, 400)); float desired_rate = 0.0f; const float mid_stick = get_throttle_mid(); diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 4a48717a8f..1380b6d0f4 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -268,15 +268,15 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi #if MODE_ACRO_ENABLED == ENABLED switch(ch_flag) { case AuxSwitchPos::LOW: - copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::OFF; + copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::OFF); AP::logger().Write_Event(LogEvent::ACRO_TRAINER_OFF); break; case AuxSwitchPos::MIDDLE: - copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::LEVELING; + copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LEVELING); AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LEVELING); break; case AuxSwitchPos::HIGH: - copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::LIMITED; + copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LIMITED); AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LIMITED); break; } diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index ab722e4ca3..5e24bd2b40 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -102,7 +102,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) } // disable throttle failsafe - g.failsafe_throttle = FS_THR_DISABLED; + g.failsafe_throttle.set(FS_THR_DISABLED); // disable motor compensation compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED); diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index d7628c2200..7d5f6e9371 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -1505,7 +1505,7 @@ public: bool is_autopilot() const override { return false; } bool logs_attitude() const override { return true; } - void set_magnitude(float input) { waveform_magnitude = input; } + void set_magnitude(float input) { waveform_magnitude.set(input); } static const struct AP_Param::GroupInfo var_info[]; diff --git a/ArduCopter/mode_turtle.cpp b/ArduCopter/mode_turtle.cpp index 72a431c0f7..4c896ea925 100644 --- a/ArduCopter/mode_turtle.cpp +++ b/ArduCopter/mode_turtle.cpp @@ -29,9 +29,9 @@ bool ModeTurtle::init(bool ignore_checks) change_motor_direction(true); // disable throttle and gps failsafe - g.failsafe_throttle = FS_THR_DISABLED; - g.failsafe_gcs = FS_GCS_DISABLED; - g.fs_ekf_action = 0; + g.failsafe_throttle.set(FS_THR_DISABLED); + g.failsafe_gcs.set(FS_GCS_DISABLED); + g.fs_ekf_action.set(0); // arm motors->armed(true); diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index b222e24f49..13114e1744 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -159,9 +159,9 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t } // disable throttle and gps failsafe - g.failsafe_throttle = FS_THR_DISABLED; - g.failsafe_gcs = FS_GCS_DISABLED; - g.fs_ekf_action = 0; + g.failsafe_throttle.set(FS_THR_DISABLED); + g.failsafe_gcs.set(FS_GCS_DISABLED); + g.fs_ekf_action.set(0); // turn on notify leds AP_Notify::flags.esc_calibration = true;