SITL: added a vectored tilt tricopter quadplane

This commit is contained in:
Andrew Tridgell 2017-04-23 12:43:28 +10:00
parent b1f1ace736
commit 1e69508322
2 changed files with 12 additions and 0 deletions

View File

@ -97,6 +97,13 @@ static Motor tilttri_motors[] =
Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, AP_MOTORS_MOT_7, 60, -60, -1, 0, 0),
};
static Motor tilttri_vectored_motors[] =
{
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, 7, 10, -90),
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3, -1, 0, 0, 8, 10, -90),
Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2)
};
static Motor y6_motors[] =
{
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
@ -135,6 +142,7 @@ static Frame supported_frames[] =
Frame("octa-quad", 8, octa_quad_motors),
Frame("octa", 8, octa_motors),
Frame("tri", 3, tri_motors),
Frame("tilttrivec",3, tilttri_vectored_motors),
Frame("tilttri", 3, tilttri_motors),
Frame("y6", 6, y6_motors),
Frame("firefly", 6, firefly_motors)

View File

@ -45,6 +45,10 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
frame_type = "y6";
} else if (strstr(frame_str, "-tri")) {
frame_type = "tri";
} else if (strstr(frame_str, "-tilttrivec")) {
frame_type = "tilttrivec";
// fwd motor gives zero thrust
thrust_scale = 0;
} else if (strstr(frame_str, "-tilttri")) {
frame_type = "tilttri";
// fwd motor gives zero thrust