Copter: Rename output_min() to enable_motor_output()

This commit is contained in:
Robert Lefebvre 2015-04-22 14:59:34 -04:00 committed by Randy Mackay
parent 41a6cc64ff
commit 05f18bb014
4 changed files with 6 additions and 6 deletions

View File

@ -124,7 +124,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan)
// enable motors and pass through throttle // enable motors and pass through throttle
init_rc_out(); init_rc_out();
output_min(); enable_motor_output();
motors.armed(true); motors.armed(true);
// initialise run time // initialise run time

View File

@ -111,7 +111,7 @@ static uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_se
// enable and arm motors // enable and arm motors
if (!motors.armed()) { if (!motors.armed()) {
init_rc_out(); init_rc_out();
output_min(); enable_motor_output();
motors.armed(true); motors.armed(true);
} }

View File

@ -207,7 +207,7 @@ static bool init_arm_motors(bool arming_from_gcs)
delay(30); delay(30);
// enable output to motors // enable output to motors
output_min(); enable_motor_output();
// finally actually arm the motors // finally actually arm the motors
motors.armed(true); motors.armed(true);

View File

@ -65,7 +65,7 @@ static void init_rc_out()
// enable output to motors // enable output to motors
pre_arm_rc_checks(); pre_arm_rc_checks();
if (ap.pre_arm_rc_check) { if (ap.pre_arm_rc_check) {
output_min(); enable_motor_output();
} }
// setup correct scaling for ESCs like the UAVCAN PX4ESC which // setup correct scaling for ESCs like the UAVCAN PX4ESC which
@ -74,8 +74,8 @@ static void init_rc_out()
hal.rcout->set_esc_scaling(g.rc_3.radio_min, g.rc_3.radio_max); hal.rcout->set_esc_scaling(g.rc_3.radio_min, g.rc_3.radio_max);
} }
// output_min - enable and output lowest possible value to motors // enable_motor_output() - enable and output lowest possible value to motors
void output_min() void enable_motor_output()
{ {
// enable motors // enable motors
motors.enable(); motors.enable();