Browse Source

AP_Motors: example sketch uses AP_Motors set_desired_spool_state

master
Randy Mackay 9 years ago
parent
commit
361b64f817
  1. 2
      libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp

2
libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp

@ -160,7 +160,7 @@ void stability_test() @@ -160,7 +160,7 @@ void stability_test()
motors.set_roll(pitch_in/4500.0f);
motors.set_yaw(yaw_in/4500.0f);
motors.set_throttle(throttle_in);
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
#if HELI_TEST == 0
motors.set_throttle_mix_mid();
#endif

Loading…
Cancel
Save