mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: set update rate to 50hz during esc calibration
Also modified some comments in the code re the esc calibration
This commit is contained in:
parent
fd14cf81f6
commit
eca6ca2100
@ -86,7 +86,7 @@ static void init_rc_out()
|
|||||||
if(g.esc_calibrate == 0) {
|
if(g.esc_calibrate == 0) {
|
||||||
// we will enter esc_calibrate mode on next reboot
|
// we will enter esc_calibrate mode on next reboot
|
||||||
g.esc_calibrate.set_and_save(1);
|
g.esc_calibrate.set_and_save(1);
|
||||||
// send miinimum throttle out to ESC
|
// send minimum throttle out to ESC
|
||||||
motors.output_min();
|
motors.output_min();
|
||||||
// display message on console
|
// display message on console
|
||||||
cliSerial->printf_P(PSTR("Entering ESC Calibration: please restart APM.\n"));
|
cliSerial->printf_P(PSTR("Entering ESC Calibration: please restart APM.\n"));
|
||||||
@ -99,7 +99,7 @@ static void init_rc_out()
|
|||||||
cliSerial->printf_P(PSTR("ESC Calibration active: passing throttle through to ESCs.\n"));
|
cliSerial->printf_P(PSTR("ESC Calibration active: passing throttle through to ESCs.\n"));
|
||||||
// clear esc flag
|
// clear esc flag
|
||||||
g.esc_calibrate.set_and_save(0);
|
g.esc_calibrate.set_and_save(0);
|
||||||
// block until we restart
|
// pass through user throttle to escs
|
||||||
init_esc();
|
init_esc();
|
||||||
}
|
}
|
||||||
}else{
|
}else{
|
||||||
|
@ -1095,6 +1095,8 @@ static void print_enabled(bool b)
|
|||||||
static void
|
static void
|
||||||
init_esc()
|
init_esc()
|
||||||
{
|
{
|
||||||
|
// reduce update rate to motors to 50Hz
|
||||||
|
motors.set_update_rate(50);
|
||||||
motors.enable();
|
motors.enable();
|
||||||
motors.armed(true);
|
motors.armed(true);
|
||||||
while(1) {
|
while(1) {
|
||||||
|
Loading…
Reference in New Issue
Block a user