SITL: setup simulator to match firefly6 AvA servo outputs
This commit is contained in:
parent
00711f5a98
commit
0171b64feb
@ -112,12 +112,12 @@ static Motor y6_motors[] =
|
||||
*/
|
||||
static Motor firefly_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, -1, 0, 0, 8, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5, -1, 0, 0, 8, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_3, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6, -1, 0, 0, 8, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_1, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_2, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, 6, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_3, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5, -1, 0, 0, 6, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
Motor(AP_MOTORS_MOT_5, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1, -1, 0, 0, 8, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_6, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3)
|
||||
Motor(AP_MOTORS_MOT_5, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2, -1, 0, 0, 6, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_6, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6, -1, 0, 0, 6, 0, -90)
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -221,6 +221,9 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel
|
||||
aileron = (ch2-ch1)/2.0f;
|
||||
// the minus does away with the need for RC2_REV=-1
|
||||
elevator = -(ch2+ch1)/2.0f;
|
||||
|
||||
// assume no rudder
|
||||
rudder = 0;
|
||||
} else if (vtail) {
|
||||
// fake a vtail plane
|
||||
float ch1 = elevator;
|
||||
|
@ -27,7 +27,8 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
|
||||
{
|
||||
// default to X frame
|
||||
const char *frame_type = "x";
|
||||
|
||||
uint8_t motor_offset = 4;
|
||||
|
||||
if (strstr(frame_str, "-octa-quad")) {
|
||||
frame_type = "octa-quad";
|
||||
} else if (strstr(frame_str, "-octaquad")) {
|
||||
@ -54,6 +55,8 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
|
||||
elevons = true;
|
||||
// fwd motor gives zero thrust
|
||||
thrust_scale = 0;
|
||||
// vtol motors start at 2
|
||||
motor_offset = 2;
|
||||
} else if (strstr(frame_str, "cl84")) {
|
||||
frame_type = "tilttri";
|
||||
// fwd motor gives zero thrust
|
||||
@ -74,7 +77,7 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
|
||||
}
|
||||
|
||||
// leave first 4 servos free for plane
|
||||
frame->motor_offset = 4;
|
||||
frame->motor_offset = motor_offset;
|
||||
|
||||
// we use zero terminal velocity to let the plane model handle the drag
|
||||
frame->init(mass, 0.51, 0, 0);
|
||||
|
Loading…
Reference in New Issue
Block a user