Browse Source

AP_Motors: example sketch provides roll, pitch, yaw in -1 to +1 range

mission-4.1.18
Randy Mackay 9 years ago
parent
commit
d4998089c8
  1. 6
      libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp

6
libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp

@ -156,9 +156,9 @@ void stability_test()
pitch_in = rpy_tests[p]; pitch_in = rpy_tests[p];
yaw_in = rpy_tests[y]; yaw_in = rpy_tests[y];
throttle_in = throttle_tests[t]/1000.0f; throttle_in = throttle_tests[t]/1000.0f;
motors.set_pitch(roll_in); motors.set_pitch(roll_in/4500.0f);
motors.set_roll(pitch_in); motors.set_roll(pitch_in/4500.0f);
motors.set_yaw(yaw_in); motors.set_yaw(yaw_in/4500.0f);
motors.set_throttle(throttle_in); motors.set_throttle(throttle_in);
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
#if HELI_TEST == 0 #if HELI_TEST == 0

Loading…
Cancel
Save