Motors: add loop_rate to test sketch

This commit is contained in:
Randy Mackay 2015-02-21 15:51:04 +09:00
parent bae424fa88
commit 80b498f598
2 changed files with 14 additions and 14 deletions

View File

@ -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

View File

@ -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