From 2eb09b291037979ee0821c7c7679d06240c045f8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Jul 2019 16:49:16 +1000 Subject: [PATCH] SITL: simple implementation of a fast jet just increase the weight and the rest can be done with params --- libraries/SITL/SIM_Plane.cpp | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/libraries/SITL/SIM_Plane.cpp b/libraries/SITL/SIM_Plane.cpp index 2d8beb37c2..4463f2535b 100644 --- a/libraries/SITL/SIM_Plane.cpp +++ b/libraries/SITL/SIM_Plane.cpp @@ -40,6 +40,11 @@ Plane::Plane(const char *home_str, const char *frame_str) : if (strstr(frame_str, "-heavy")) { mass = 8; } + if (strstr(frame_str, "-jet")) { + // a 22kg "jet", level top speed is 102m/s + mass = 22; + thrust_scale = (mass * GRAVITY_MSS) / hover_throttle; + } if (strstr(frame_str, "-revthrust")) { reverse_thrust = true; } @@ -68,11 +73,11 @@ Plane::Plane(const char *home_str, const char *frame_str) : launch_accel = 10; launch_time = 1; } - if (strstr(frame_str, "-tailsitter")) { - tailsitter = true; - ground_behavior = GROUND_BEHAVIOR_TAILSITTER; - thrust_scale *= 1.5; - } + if (strstr(frame_str, "-tailsitter")) { + tailsitter = true; + ground_behavior = GROUND_BEHAVIOR_TAILSITTER; + thrust_scale *= 1.5; + } if (strstr(frame_str, "-ice")) { ice_engine = true;