From 05f18bb014c3a5bc25bb24eab8c93731731ead56 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Wed, 22 Apr 2015 14:59:34 -0400 Subject: [PATCH] Copter: Rename output_min() to enable_motor_output() --- ArduCopter/compassmot.pde | 2 +- ArduCopter/motor_test.pde | 2 +- ArduCopter/motors.pde | 2 +- ArduCopter/radio.pde | 6 +++--- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/compassmot.pde b/ArduCopter/compassmot.pde index e682dce290..ec2ea4d1d9 100644 --- a/ArduCopter/compassmot.pde +++ b/ArduCopter/compassmot.pde @@ -124,7 +124,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan) // enable motors and pass through throttle init_rc_out(); - output_min(); + enable_motor_output(); motors.armed(true); // initialise run time diff --git a/ArduCopter/motor_test.pde b/ArduCopter/motor_test.pde index 12590cec97..ba23df3df9 100644 --- a/ArduCopter/motor_test.pde +++ b/ArduCopter/motor_test.pde @@ -111,7 +111,7 @@ static uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_se // enable and arm motors if (!motors.armed()) { init_rc_out(); - output_min(); + enable_motor_output(); motors.armed(true); } diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index cc6b31bc85..7f18523ce7 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -207,7 +207,7 @@ static bool init_arm_motors(bool arming_from_gcs) delay(30); // enable output to motors - output_min(); + enable_motor_output(); // finally actually arm the motors motors.armed(true); diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index c47781bf5a..96a3c7ffd9 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -65,7 +65,7 @@ static void init_rc_out() // enable output to motors pre_arm_rc_checks(); if (ap.pre_arm_rc_check) { - output_min(); + enable_motor_output(); } // 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); } -// output_min - enable and output lowest possible value to motors -void output_min() +// enable_motor_output() - enable and output lowest possible value to motors +void enable_motor_output() { // enable motors motors.enable();