mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: rename set_servos_4 to motors_output
This commit is contained in:
parent
3550e52560
commit
64af4ff923
@ -970,9 +970,8 @@ static void fast_loop()
|
||||
update_heli_control_dynamics();
|
||||
#endif //HELI_FRAME
|
||||
|
||||
// write out the servo PWM values
|
||||
// ------------------------------
|
||||
set_servos_4();
|
||||
// send outputs to the motors library
|
||||
motors_output();
|
||||
|
||||
// Inertial Nav
|
||||
// --------------------
|
||||
|
@ -684,11 +684,8 @@ static void init_disarm_motors()
|
||||
ahrs.set_armed(false);
|
||||
}
|
||||
|
||||
/*****************************************
|
||||
* Set the flight control servos based on the current calculated values
|
||||
*****************************************/
|
||||
static void
|
||||
set_servos_4()
|
||||
// motors_output - send output to motors library which will adjust and send to ESCs and servos
|
||||
static void motors_output()
|
||||
{
|
||||
// check if we are performing the motor test
|
||||
if (ap.motor_test) {
|
||||
|
Loading…
Reference in New Issue
Block a user