mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
SITL: Added DJI Hexa and Octa for SITL
This commit is contained in:
parent
38533b2f09
commit
dc662a56b2
@ -105,6 +105,16 @@ static Motor hexax_motors[] =
|
|||||||
Motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4)
|
Motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4)
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static Motor hexa_dji_x_motors[] =
|
||||||
|
{
|
||||||
|
Motor(AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||||
|
Motor(AP_MOTORS_MOT_2, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
|
||||||
|
Motor(AP_MOTORS_MOT_3, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||||
|
Motor(AP_MOTORS_MOT_4, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||||
|
Motor(AP_MOTORS_MOT_5, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||||
|
Motor(AP_MOTORS_MOT_6, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2)
|
||||||
|
};
|
||||||
|
|
||||||
static Motor octa_motors[] =
|
static Motor octa_motors[] =
|
||||||
{
|
{
|
||||||
Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
|
Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
|
||||||
@ -117,6 +127,18 @@ static Motor octa_motors[] =
|
|||||||
Motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3)
|
Motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3)
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static Motor octa_dji_x_motors[] =
|
||||||
|
{
|
||||||
|
Motor(AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||||
|
Motor(AP_MOTORS_MOT_2, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8),
|
||||||
|
Motor(AP_MOTORS_MOT_3, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7),
|
||||||
|
Motor(AP_MOTORS_MOT_4, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
|
||||||
|
Motor(AP_MOTORS_MOT_5, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||||
|
Motor(AP_MOTORS_MOT_6, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||||
|
Motor(AP_MOTORS_MOT_7, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||||
|
Motor(AP_MOTORS_MOT_8, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2)
|
||||||
|
};
|
||||||
|
|
||||||
static Motor octa_quad_motors[] =
|
static Motor octa_quad_motors[] =
|
||||||
{
|
{
|
||||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||||
@ -205,7 +227,9 @@ static Frame supported_frames[] =
|
|||||||
Frame("cwx", 4, quad_cw_x_motors),
|
Frame("cwx", 4, quad_cw_x_motors),
|
||||||
Frame("tilthvec", 4, tiltquad_h_vectored_motors),
|
Frame("tilthvec", 4, tiltquad_h_vectored_motors),
|
||||||
Frame("hexax", 6, hexax_motors),
|
Frame("hexax", 6, hexax_motors),
|
||||||
|
Frame("hexa-dji", 6, hexa_dji_x_motors),
|
||||||
Frame("hexa", 6, hexa_motors),
|
Frame("hexa", 6, hexa_motors),
|
||||||
|
Frame("octa-dji", 8, octa_dji_x_motors),
|
||||||
Frame("octa-quad", 8, octa_quad_motors),
|
Frame("octa-quad", 8, octa_quad_motors),
|
||||||
Frame("octa", 8, octa_motors),
|
Frame("octa", 8, octa_motors),
|
||||||
Frame("dodeca-hexa", 12, dodeca_hexa_motors),
|
Frame("dodeca-hexa", 12, dodeca_hexa_motors),
|
||||||
|
Loading…
Reference in New Issue
Block a user