|
|
|
@ -37,8 +37,13 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
@@ -37,8 +37,13 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
|
|
|
|
|
Plane(home_str, frame_str) |
|
|
|
|
{ |
|
|
|
|
frame = &quad_frame; |
|
|
|
|
// we use a very high terminal velocity to let the plane model handle the drag
|
|
|
|
|
frame->init(mass, 0.51, 100, 20*radians(360)); |
|
|
|
|
// we use zero terminal velocity to let the plane model handle the drag
|
|
|
|
|
frame->init(mass, 0.51, 0, 0); |
|
|
|
|
|
|
|
|
|
// see if we want a tiltrotor
|
|
|
|
|
if (strstr(frame_str, "-tilt")) { |
|
|
|
|
tiltrotors = true; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
@ -56,6 +61,19 @@ void QuadPlane::update(const struct sitl_input &input)
@@ -56,6 +61,19 @@ void QuadPlane::update(const struct sitl_input &input)
|
|
|
|
|
|
|
|
|
|
frame->calculate_forces(*this, input, quad_rot_accel, quad_accel_body); |
|
|
|
|
|
|
|
|
|
if (tiltrotors) { |
|
|
|
|
// get rotor tilt from channel 9
|
|
|
|
|
float tilt = constrain_float(-90 * (input.servos[8]-1000)*0.001, -90, 0); |
|
|
|
|
|
|
|
|
|
// rotate the rotational accel and body accel from multicopter
|
|
|
|
|
// model to take account of rotor tilt
|
|
|
|
|
Matrix3f rotation; |
|
|
|
|
rotation.identity(); |
|
|
|
|
rotation.rotate(Vector3f(0, radians(tilt), 0)); |
|
|
|
|
quad_rot_accel = rotation * quad_rot_accel; |
|
|
|
|
quad_accel_body = rotation * quad_accel_body; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
rot_accel += quad_rot_accel; |
|
|
|
|
accel_body += quad_accel_body; |
|
|
|
|
|
|
|
|
|