Browse Source

Copter: rename set_servos_4 to motors_output

mission-4.1.18
Randy Mackay 10 years ago
parent
commit
64af4ff923
  1. 5
      ArduCopter/ArduCopter.pde
  2. 7
      ArduCopter/motors.pde

5
ArduCopter/ArduCopter.pde

@ -970,9 +970,8 @@ static void fast_loop() @@ -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
// --------------------

7
ArduCopter/motors.pde

@ -684,11 +684,8 @@ static void init_disarm_motors() @@ -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…
Cancel
Save