mirror of https://github.com/ArduPilot/ardupilot
Copter: Rename output_min() to enable_motor_output()
This commit is contained in:
parent
41a6cc64ff
commit
05f18bb014
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue