SITL: support a builtin tailsitter vehicle type

This commit is contained in:
Andrew Tridgell 2017-02-11 22:30:42 +11:00
parent 92fdef5b97
commit 3c8020862c
4 changed files with 23 additions and 2 deletions

View File

@ -508,6 +508,19 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
use_smoothing = true;
break;
}
case GROUND_BEHAVIOR_TAILSITTER: {
// point straight up
float r, p, y;
dcm.to_euler(&r, &p, &y);
dcm.from_euler(0.0f, radians(90), y);
// no movement
if (accel_earth.z > -1.1*GRAVITY_MSS) {
velocity_ef.zero();
}
gyro.zero();
use_smoothing = true;
break;
}
}
}
}

View File

@ -163,6 +163,7 @@ protected:
GROUND_BEHAVIOR_NONE = 0,
GROUND_BEHAVIOR_NO_MOVEMENT,
GROUND_BEHAVIOR_FWD_ONLY,
GROUND_BEHAVIOR_TAILSITTER,
} ground_behavior;
bool use_smoothing;

View File

@ -35,6 +35,8 @@ Plane::Plane(const char *home_str, const char *frame_str) :
thrust_scale = (mass * GRAVITY_MSS) / hover_throttle;
frame_height = 0.1f;
ground_behavior = GROUND_BEHAVIOR_FWD_ONLY;
if (strstr(frame_str, "-heavy")) {
mass = 8;
}
@ -49,8 +51,12 @@ Plane::Plane(const char *home_str, const char *frame_str) :
if (strstr(frame_str, "-elevrev")) {
reverse_elevator_rudder = true;
}
if (strstr(frame_str, "-tailsitter")) {
tailsitter = true;
ground_behavior = GROUND_BEHAVIOR_TAILSITTER;
thrust_scale *= 1.5;
}
ground_behavior = GROUND_BEHAVIOR_FWD_ONLY;
if (strstr(frame_str, "-ice")) {
ice_engine = true;
}
@ -266,7 +272,7 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel
add_noise(fabsf(thrust) / thrust_scale);
}
if (on_ground()) {
if (on_ground() && !tailsitter) {
// add some ground friction
Vector3f vel_body = dcm.transposed() * velocity_ef;
accel_body.x -= vel_body.x * 0.3f;

View File

@ -97,6 +97,7 @@ protected:
bool vtail;
bool reverse_elevator_rudder;
bool ice_engine;
bool tailsitter;
ICEngine icengine{2, 14, 12, 13, 100};