mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
SITL: load plane-3d.parm when -f plane-3d is chosen
this gets the right parameters in MissionPlanner SITL
This commit is contained in:
parent
98145f7a3f
commit
7942b58fba
@ -85,6 +85,9 @@ Plane::Plane(const char *frame_str) :
|
||||
if (strstr(frame_str, "-3d")) {
|
||||
aerobatic = true;
|
||||
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")) {
|
||||
|
@ -16,7 +16,7 @@ PLANE=$ROOTDIR/build/sitl/bin/arduplane
|
||||
#UARTA="tcp:0"
|
||||
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"
|
||||
|
||||
mkdir -p swarm/plane swarm/copter
|
||||
|
Loading…
Reference in New Issue
Block a user