mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
SITL: Support for decacopters
This commit is contained in:
parent
159a6c7ed6
commit
13c7980f0b
@ -205,6 +205,34 @@ static Motor dodeca_hexa_motors[] =
|
||||
Motor(AP_MOTORS_MOT_12, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12)
|
||||
};
|
||||
|
||||
static Motor deca_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_3, 72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, 108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
Motor(AP_MOTORS_MOT_5, 144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||
Motor(AP_MOTORS_MOT_6, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
|
||||
Motor(AP_MOTORS_MOT_7, -144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7),
|
||||
Motor(AP_MOTORS_MOT_8, -108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8),
|
||||
Motor(AP_MOTORS_MOT_9, -72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9),
|
||||
Motor(AP_MOTORS_MOT_10, -36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10)
|
||||
};
|
||||
|
||||
static Motor deca_cw_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 18, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 54, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_3, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, 126, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
Motor(AP_MOTORS_MOT_5, 162, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||
Motor(AP_MOTORS_MOT_6, -162, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
|
||||
Motor(AP_MOTORS_MOT_7, -126, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7),
|
||||
Motor(AP_MOTORS_MOT_8, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8),
|
||||
Motor(AP_MOTORS_MOT_9, -54, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9),
|
||||
Motor(AP_MOTORS_MOT_10, -18, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10)
|
||||
};
|
||||
|
||||
static Motor tri_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
@ -273,6 +301,8 @@ static Frame supported_frames[] =
|
||||
Frame("octa-quad-cwx",8, octa_quad_cw_x_motors),
|
||||
Frame("octa-quad", 8, octa_quad_motors),
|
||||
Frame("octa", 8, octa_motors),
|
||||
Frame("deca", 10, deca_motors),
|
||||
Frame("deca-cwx", 10, deca_cw_x_motors),
|
||||
Frame("dodeca-hexa", 12, dodeca_hexa_motors),
|
||||
Frame("tri", 3, tri_motors),
|
||||
Frame("tilttrivec",3, tilttri_vectored_motors),
|
||||
|
Loading…
Reference in New Issue
Block a user