mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
SITL: improved AirSim quadX tuning
and move params to normal location, so they are found with sim_vehicle.py
This commit is contained in:
parent
d657fed34a
commit
061d778bfd
20
Tools/autotest/default_params/airsim-quadX.parm
Normal file
20
Tools/autotest/default_params/airsim-quadX.parm
Normal file
@ -0,0 +1,20 @@
|
||||
ATC_RAT_PIT_D 0.003
|
||||
ATC_RAT_PIT_I 0.25
|
||||
ATC_RAT_PIT_P 0.25
|
||||
ATC_RAT_RLL_D 0.003
|
||||
ATC_RAT_RLL_I 0.25
|
||||
ATC_RAT_RLL_P 0.25
|
||||
DISARM_DELAY 0.000000
|
||||
FRAME_TYPE 1.000000
|
||||
FS_CRASH_CHECK 0.000000
|
||||
LOG_BITMASK 65535
|
||||
MOT_THST_HOVER 0.461
|
||||
MOT_THST_EXPO 0.0
|
||||
SCHED_LOOP_RATE 300
|
||||
WPNAV_ACCEL 400
|
||||
WPNAV_ACCEL_Z 200
|
||||
WPNAV_SPEED_UP 400
|
||||
WPNAV_SPEED_DN 300
|
||||
WPNAV_SPEED 2000
|
||||
RTL_ALT 2500
|
||||
ANGLE_MAX 3000
|
@ -94,7 +94,8 @@ class VehicleInfo(object):
|
||||
},
|
||||
"airsim-copter": {
|
||||
"waf_target": "bin/arducopter",
|
||||
"default_params_filename": "default_params/copter.parm",
|
||||
"default_params_filename": ["default_params/copter.parm",
|
||||
"default_params/airsim-quadX.parm"],
|
||||
},
|
||||
# HELICOPTER
|
||||
"heli": {
|
||||
|
@ -1,14 +0,0 @@
|
||||
ATC_RAT_PIT_D 0.001000
|
||||
ATC_RAT_PIT_I 0.070000
|
||||
ATC_RAT_PIT_P 0.070000
|
||||
ATC_RAT_RLL_D 0.001000
|
||||
ATC_RAT_RLL_I 0.070000
|
||||
ATC_RAT_RLL_P 0.070000
|
||||
AUTOTUNE_AXES 1.000000
|
||||
DISARM_DELAY 0.000000
|
||||
FRAME_TYPE 1.000000
|
||||
FS_CRASH_CHECK 0.000000
|
||||
LOG_BITMASK 65535.000000
|
||||
MOT_THST_HOVER 0.416806
|
||||
PSC_POSZ_P 0.500000
|
||||
PSC_VELZ_P 2.000000
|
@ -1,16 +1,2 @@
|
||||
ATC_RAT_PIT_D 0.001000
|
||||
ATC_RAT_PIT_I 0.070000
|
||||
ATC_RAT_PIT_P 0.070000
|
||||
ATC_RAT_RLL_D 0.001000
|
||||
ATC_RAT_RLL_I 0.070000
|
||||
ATC_RAT_RLL_P 0.070000
|
||||
AUTOTUNE_AXES 1.000000
|
||||
DISARM_DELAY 0.000000
|
||||
FRAME_TYPE 1.000000
|
||||
FS_CRASH_CHECK 0.000000
|
||||
LOG_BITMASK 65535.000000
|
||||
MOT_THST_HOVER 0.416806
|
||||
PSC_POSZ_P 0.500000
|
||||
PSC_VELZ_P 2.000000
|
||||
PRX_TYPE 12
|
||||
AVOID_ENABLE 7
|
||||
|
Loading…
Reference in New Issue
Block a user