Browse Source

ArduCopter: params always use set method

apm_2208
Iampete1 3 years ago committed by Peter Hall
parent
commit
ac94ba33ff
  1. 2
      ArduCopter/Attitude.cpp
  2. 6
      ArduCopter/RC_Channel.cpp
  3. 2
      ArduCopter/compassmot.cpp
  4. 2
      ArduCopter/mode.h
  5. 6
      ArduCopter/mode_turtle.cpp
  6. 6
      ArduCopter/motor_test.cpp

2
ArduCopter/Attitude.cpp

@ -58,7 +58,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control) @@ -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();

6
ArduCopter/RC_Channel.cpp

@ -268,15 +268,15 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi @@ -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;
}

2
ArduCopter/compassmot.cpp

@ -102,7 +102,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -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);

2
ArduCopter/mode.h

@ -1505,7 +1505,7 @@ public: @@ -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[];

6
ArduCopter/mode_turtle.cpp

@ -29,9 +29,9 @@ bool ModeTurtle::init(bool ignore_checks) @@ -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);

6
ArduCopter/motor_test.cpp

@ -159,9 +159,9 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t @@ -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;

Loading…
Cancel
Save