mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Tools: autotest: update sailboat default params and add sailboat-motor frame
This commit is contained in:
parent
4afcc9c289
commit
ac237eea4b
16
Tools/autotest/default_params/sailboat-motor.parm
Normal file
16
Tools/autotest/default_params/sailboat-motor.parm
Normal file
@ -0,0 +1,16 @@
|
|||||||
|
FRAME_CLASS 2
|
||||||
|
LOIT_TYPE 1
|
||||||
|
LOIT_RADIUS 5
|
||||||
|
MOT_SLEWRATE 0
|
||||||
|
SERVO4_FUNCTION 89
|
||||||
|
SERVO4_MIN 1000
|
||||||
|
SERVO4_MAX 2000
|
||||||
|
SIM_WIND_SPD 3
|
||||||
|
SIM_WIND_T 1
|
||||||
|
WNDVN_TYPE 10
|
||||||
|
WNDVN_SPEED_TYPE 10
|
||||||
|
WP_OVERSHOOT 10
|
||||||
|
SAIL_ENABLE 1
|
||||||
|
RPM_MIN 0
|
||||||
|
RPM_TYPE 3
|
||||||
|
ARSPD_OFFSET 2013
|
@ -14,3 +14,4 @@ SAIL_ENABLE 1
|
|||||||
RPM_MIN 0
|
RPM_MIN 0
|
||||||
RPM_TYPE 3
|
RPM_TYPE 3
|
||||||
ARSPD_OFFSET 2013
|
ARSPD_OFFSET 2013
|
||||||
|
SERVO3_FUNCTION 0
|
||||||
|
@ -242,6 +242,11 @@ class VehicleInfo(object):
|
|||||||
"default_params_filename": ["default_params/rover.parm",
|
"default_params_filename": ["default_params/rover.parm",
|
||||||
"default_params/sailboat.parm"],
|
"default_params/sailboat.parm"],
|
||||||
},
|
},
|
||||||
|
"sailboat-motor": {
|
||||||
|
"waf_target": "bin/ardurover",
|
||||||
|
"default_params_filename": ["default_params/rover.parm",
|
||||||
|
"default_params/sailboat-motor.parm"],
|
||||||
|
},
|
||||||
"gazebo-rover": {
|
"gazebo-rover": {
|
||||||
"waf_target": "bin/ardurover",
|
"waf_target": "bin/ardurover",
|
||||||
"default_params_filename": ["default_params/rover.parm",
|
"default_params_filename": ["default_params/rover.parm",
|
||||||
|
Loading…
Reference in New Issue
Block a user