Browse Source

Copter: fixed ESC calibration on Pixhawk

this ensures motors are armed after safety is pressed, and also gives
print out of channel inputs and outputs on USB console for debug
purposes

Pair-Programmed-With: Randy Mackay <rmackay9@yahoo.com>
master
Andrew Tridgell 11 years ago
parent
commit
91ec4e56d5
  1. 18
      ArduCopter/setup.pde

18
ArduCopter/setup.pde

@ -468,14 +468,24 @@ init_esc() @@ -468,14 +468,24 @@ init_esc()
// reduce update rate to motors to 50Hz
motors.set_update_rate(50);
// we enable the motors directly here instead of calling output_min because output_min would send a low signal to the ESC and disrupt the calibration process
motors.enable();
motors.armed(true);
uint32_t last_print_ms = 0;
while(1) {
motors.armed(true);
motors.enable();
read_radio();
delay(100);
delay(10);
AP_Notify::flags.esc_calibration = true;
motors.throttle_pass_through();
uint32_t now = hal.scheduler->millis();
if (now - last_print_ms > 1000) {
hal.console->printf_P(PSTR("ESC cal input: %u %u %u %u output: %u %u %u %u\n"),
(unsigned)hal.rcin->read(0), (unsigned)hal.rcin->read(1),
(unsigned)hal.rcin->read(2), (unsigned)hal.rcin->read(3),
(unsigned)hal.rcout->read(0), (unsigned)hal.rcout->read(1),
(unsigned)hal.rcout->read(2), (unsigned)hal.rcout->read(3));
last_print_ms = now;
}
}
}

Loading…
Cancel
Save