Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: added plane-3d frame #22000

Merged
merged 2 commits into from Oct 19, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
29 changes: 29 additions & 0 deletions Tools/autotest/default_params/plane-3d.parm
@@ -0,0 +1,29 @@
RLL2SRV_RMAX 75.000000
RLL_RATE_P 0.253315
RLL_RATE_I 0.039625
RLL_RATE_D 0.005096
RLL_RATE_FF 0.039625
RLL_RATE_FLTT 3.183099
RLL_RATE_FLTD 10.000000
PTCH2SRV_TCONST 0.750000
PTCH2SRV_RMAX_UP 75.000000
PTCH2SRV_RMAX_DN 75.000000
PTCH_RATE_P 0.361746
PTCH_RATE_I 0.271310
PTCH_RATE_D 0.007887
PTCH_RATE_FF 0.063623
PTCH_RATE_FLTT 2.122066
PTCH_RATE_FLTD 10.00000
YAW_RATE_ENABLE 1.000000
YAW_RATE_P 0.422192
YAW_RATE_I 0.548437
YAW_RATE_D 0.030000
YAW_RATE_FF 0.548437
YAW_RATE_FLTT 3.183099
YAW_RATE_FLTD 10.000000
YAW_RATE_SMAX 200.000000
YAW_RATE_SMAX 200.0
ACRO_YAW_RATE 60
AHRS_EKF_TYPE 10
TRIM_THROTTLE 30
NAVL1_PERIOD 7
4 changes: 4 additions & 0 deletions Tools/autotest/pysim/vehicleinfo.py
Expand Up @@ -274,6 +274,10 @@ def __init__(self):
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/plane.parm", "default_params/plane-ice.parm"],
},
"plane-3d": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/plane.parm", "default_params/plane-3d.parm"],
},
"quadplane-copter_tailsitter": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm","default_params/quadplane-copter_tailsitter.parm"],
Expand Down
9 changes: 7 additions & 2 deletions libraries/SITL/SIM_Plane.cpp
Expand Up @@ -82,6 +82,11 @@ Plane::Plane(const char *frame_str) :
thrust_scale *= 1.5;
}

if (strstr(frame_str, "-3d")) {
aerobatic = true;
thrust_scale *= 1.5;
}

if (strstr(frame_str, "-ice")) {
ice_engine = true;
}
Expand Down Expand Up @@ -142,7 +147,7 @@ Vector3f Plane::getTorque(float inputAileron, float inputElevator, float inputRu
//calculate aerodynamic torque
float effective_airspeed = airspeed;

if (tailsitter) {
if (tailsitter || aerobatic) {
/*
tailsitters get airspeed from prop-wash
*/
Expand Down Expand Up @@ -321,7 +326,7 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel
angle_of_attack = atan2f(velocity_air_bf.z, velocity_air_bf.x);
beta = atan2f(velocity_air_bf.y,velocity_air_bf.x);

if (tailsitter) {
if (tailsitter || aerobatic) {
/*
tailsitters get 4x the control surfaces
*/
Expand Down
1 change: 1 addition & 0 deletions libraries/SITL/SIM_Plane.h
Expand Up @@ -99,6 +99,7 @@ class Plane : public Aircraft {
bool reverse_elevator_rudder;
bool ice_engine;
bool tailsitter;
bool aerobatic;
bool copter_tailsitter;
bool have_launcher;
float launch_accel;
Expand Down