mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Motors: add loop_rate to test sketch
This commit is contained in:
parent
bae424fa88
commit
80b498f598
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user