posix-configs: added sitl startup script for gazebo quad tiltrotor model

Signed-off-by: Roman <bapstroman@gmail.com>
This commit is contained in:
Roman
2018-02-22 11:31:15 +01:00
committed by Daniel Agar
parent 86c472d8ff
commit 2886fe8da3
2 changed files with 98 additions and 1 deletions
+1 -1
View File
@@ -47,7 +47,7 @@ ExternalProject_Add_Step(sitl_gazebo forceconfigure
# create targets for each viewer/model/debugger combination # create targets for each viewer/model/debugger combination
set(viewers none jmavsim gazebo replay) set(viewers none jmavsim gazebo replay)
set(debuggers none ide gdb lldb ddd valgrind callgrind) set(debuggers none ide gdb lldb ddd valgrind callgrind)
set(models none iris iris_opt_flow iris_rplidar iris_irlock standard_vtol plane solo tailsitter typhoon_h480 rover hippocampus) set(models none iris iris_opt_flow iris_rplidar iris_irlock standard_vtol plane solo tailsitter typhoon_h480 rover hippocampus tiltrotor)
set(all_posix_vmd_make_targets) set(all_posix_vmd_make_targets)
foreach(viewer ${viewers}) foreach(viewer ${viewers})
foreach(debugger ${debuggers}) foreach(debugger ${debuggers})
+97
View File
@@ -0,0 +1,97 @@
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MAV_TYPE 21
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 5.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 80
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_AUTOSTART 13006
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set VT_MOT_COUNT 4
param set VT_TRANS_THR 0.75
param set VT_TYPE 1
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
adcsim start
gpssim start
measairspeedsim start
pwm_out_sim mode_pwm
sensors start
commander start
land_detector start vtol
navigator start
ekf2 start
vtol_att_control start
mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/tiltrotor_sitl.main.mix
mavlink start -x -u 14556 -r 2000000 -f
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540 -f
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14557
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart