SITL: Added cwx motor setup for hexa, octa and octaquad
This commit is contained in:
parent
aec65ed6ff
commit
08f27f7668
@ -115,6 +115,16 @@ static Motor hexa_dji_x_motors[] =
|
||||
Motor(AP_MOTORS_MOT_6, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2)
|
||||
};
|
||||
|
||||
static Motor hexa_cw_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_3, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
Motor(AP_MOTORS_MOT_5, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||
Motor(AP_MOTORS_MOT_6, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6)
|
||||
};
|
||||
|
||||
static Motor octa_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
|
||||
@ -139,6 +149,18 @@ static Motor octa_dji_x_motors[] =
|
||||
Motor(AP_MOTORS_MOT_8, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2)
|
||||
};
|
||||
|
||||
static Motor octa_cw_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_3, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
Motor(AP_MOTORS_MOT_5, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||
Motor(AP_MOTORS_MOT_6, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
|
||||
Motor(AP_MOTORS_MOT_7, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7),
|
||||
Motor(AP_MOTORS_MOT_8, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8)
|
||||
};
|
||||
|
||||
static Motor octa_quad_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
@ -151,6 +173,18 @@ static Motor octa_quad_motors[] =
|
||||
Motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6)
|
||||
};
|
||||
|
||||
static Motor octa_quad_cw_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_3, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
Motor(AP_MOTORS_MOT_5, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||
Motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
|
||||
Motor(AP_MOTORS_MOT_7, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7),
|
||||
Motor(AP_MOTORS_MOT_8, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8)
|
||||
};
|
||||
|
||||
static Motor dodeca_hexa_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
@ -227,9 +261,12 @@ static Frame supported_frames[] =
|
||||
Frame("cwx", 4, quad_cw_x_motors),
|
||||
Frame("tilthvec", 4, tiltquad_h_vectored_motors),
|
||||
Frame("hexax", 6, hexax_motors),
|
||||
Frame("hexa-cwx", 6, hexa_cw_x_motors),
|
||||
Frame("hexa-dji", 6, hexa_dji_x_motors),
|
||||
Frame("hexa", 6, hexa_motors),
|
||||
Frame("octa-cwx", 8, octa_cw_x_motors),
|
||||
Frame("octa-dji", 8, octa_dji_x_motors),
|
||||
Frame("octa-quad-cwx",8, octa_quad_cw_x_motors),
|
||||
Frame("octa-quad", 8, octa_quad_motors),
|
||||
Frame("octa", 8, octa_motors),
|
||||
Frame("dodeca-hexa", 12, dodeca_hexa_motors),
|
||||
|
Loading…
Reference in New Issue
Block a user