Browse Source

Copter: removed calls to motors->enable()

master
Andrew Tridgell 8 years ago
parent
commit
c4b0d7bc35
  1. 2
      ArduCopter/esc_calibration.cpp
  2. 1
      ArduCopter/radio.cpp

2
ArduCopter/esc_calibration.cpp

@ -101,7 +101,6 @@ void Copter::esc_calibration_passthrough() @@ -101,7 +101,6 @@ void Copter::esc_calibration_passthrough()
// arm motors
motors->armed(true);
motors->enable();
SRV_Channels::enable_by_mask(motors->get_motor_mask());
hal.util->set_soft_armed(true);
@ -149,7 +148,6 @@ void Copter::esc_calibration_auto() @@ -149,7 +148,6 @@ void Copter::esc_calibration_auto()
// arm and enable motors
motors->armed(true);
motors->enable();
SRV_Channels::enable_by_mask(motors->get_motor_mask());
hal.util->set_soft_armed(true);

1
ArduCopter/radio.cpp

@ -79,7 +79,6 @@ void Copter::init_rc_out() @@ -79,7 +79,6 @@ void Copter::init_rc_out()
void Copter::enable_motor_output()
{
// enable motors
motors->enable();
motors->output_min();
}

Loading…
Cancel
Save