SITL: load plane-3d.parm when -f plane-3d is chosen

this gets the right parameters in MissionPlanner SITL
This commit is contained in:
Andrew Tridgell 2022-11-09 12:50:58 +11:00
parent 98145f7a3f
commit 7942b58fba
2 changed files with 4 additions and 1 deletions

View File

@ -85,6 +85,9 @@ Plane::Plane(const char *frame_str) :
if (strstr(frame_str, "-3d")) { if (strstr(frame_str, "-3d")) {
aerobatic = true; aerobatic = true;
thrust_scale *= 1.5; thrust_scale *= 1.5;
// setup parameters for plane-3d
AP_Param::load_defaults_file("@ROMFS/models/plane.parm", false);
AP_Param::load_defaults_file("@ROMFS/models/plane-3d.parm", false);
} }
if (strstr(frame_str, "-ice")) { if (strstr(frame_str, "-ice")) {

View File

@ -16,7 +16,7 @@ PLANE=$ROOTDIR/build/sitl/bin/arduplane
#UARTA="tcp:0" #UARTA="tcp:0"
UARTA="mcast:" UARTA="mcast:"
PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/plane.parm" PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/models/plane.parm"
COPTER_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm" COPTER_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm"
mkdir -p swarm/plane swarm/copter mkdir -p swarm/plane swarm/copter