diff --git a/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.pde b/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.pde index 11d659af01..3eb02d8fd5 100644 --- a/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.pde +++ b/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.pde @@ -41,13 +41,13 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; RC_Channel rc1(0), rc2(1), rc3(2), rc4(3); // uncomment the row below depending upon what frame you are using -//AP_MotorsTri motors(rc1, rc2, rc3, rc4); -AP_MotorsQuad motors(rc1, rc2, rc3, rc4); -//AP_MotorsHexa motors(rc1, rc2, rc3, rc4); -//AP_MotorsY6 motors(rc1, rc2, rc3, rc4); -//AP_MotorsOcta motors(rc1, rc2, rc3, rc4); -//AP_MotorsOctaQuad motors(rc1, rc2, rc3, rc4); -//AP_MotorsHeli motors(rc1, rc2, rc3, rc4); +//AP_MotorsTri motors(rc1, rc2, rc3, rc4, 400); +AP_MotorsQuad motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsHexa motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsY6 motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsOcta motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsOctaQuad motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsHeli motors(rc1, rc2, rc3, rc4, 400); // setup diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde index a1b797ef15..e9c2fea8bb 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde @@ -41,13 +41,13 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; RC_Channel rc1(0), rc2(1), rc3(2), rc4(3); // uncomment the row below depending upon what frame you are using -//AP_MotorsTri motors(rc1, rc2, rc3, rc4); -AP_MotorsQuad motors(rc1, rc2, rc3, rc4); -//AP_MotorsHexa motors(rc1, rc2, rc3, rc4); -//AP_MotorsY6 motors(rc1, rc2, rc3, rc4); -//AP_MotorsOcta motors(rc1, rc2, rc3, rc4); -//AP_MotorsOctaQuad motors(rc1, rc2, rc3, rc4); -//AP_MotorsHeli motors(rc1, rc2, rc3, rc4); +//AP_MotorsTri motors(rc1, rc2, rc3, rc4, 400); +AP_MotorsQuad motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsHexa motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsY6 motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsOcta motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsOctaQuad motors(rc1, rc2, rc3, rc4, 400); +//AP_MotorsHeli motors(rc1, rc2, rc3, rc4, 400); // setup