mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Tools: add sailboat to pysim and add default parameters
This commit is contained in:
parent
804305aa2b
commit
851de12838
7
Tools/autotest/default_params/sailboat.parm
Normal file
7
Tools/autotest/default_params/sailboat.parm
Normal file
@ -0,0 +1,7 @@
|
||||
FRAME_CLASS 2
|
||||
MOT_SLEWRATE 0
|
||||
SERVO4_FUNCTION 1
|
||||
SERVO4_MIN 1000
|
||||
SERVO4_MAX 2000
|
||||
SIM_WIND_SPD 3
|
||||
SIM_WIND_T 1
|
@ -201,6 +201,11 @@ class VehicleInfo(object):
|
||||
"default_params/rover-skid.parm",
|
||||
"default_params/balancebot.parm"],
|
||||
},
|
||||
"sailboat": {
|
||||
"waf_target": "bin/ardurover",
|
||||
"default_params_filename": ["default_params/rover.parm",
|
||||
"default_params/sailboat.parm"],
|
||||
},
|
||||
"gazebo-rover": {
|
||||
"waf_target": "bin/ardurover",
|
||||
"default_params_filename": ["default_params/rover.parm",
|
||||
|
Loading…
Reference in New Issue
Block a user