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 b0d41bc6e4..9a2663d87d 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 @@ -19,13 +19,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(AP_MOTORS_APM1, &rc1, &rc2, &rc3, &rc4); -AP_MotorsQuad motors(AP_MOTORS_APM2, &rc1, &rc2, &rc3, &rc4); -//AP_MotorsHexa motors(AP_MOTORS_APM1, &rc1, &rc2, &rc3, &rc4); -//AP_MotorsY6 motors(AP_MOTORS_APM1, &rc1, &rc2, &rc3, &rc4); -//AP_MotorsOcta motors(AP_MOTORS_APM1, &rc1, &rc2, &rc3, &rc4); -//AP_MotorsOctaQuad motors(AP_MOTORS_APM1, &rc1, &rc2, &rc3, &rc4); -//AP_MotorsHeli motors(AP_MOTORS_APM1, &rc1, &rc2, &rc3, &rc4); +//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); // setup