Add SITL Target for typhoon_h480 with airsim

This commit is contained in:
Jaeyoung-Lim
2021-11-03 20:08:25 +01:00
parent f55590ce78
commit 6369b42d71
4 changed files with 44 additions and 0 deletions
@@ -0,0 +1,31 @@
#!/bin/sh
#
# @name Typhoon H480 SITL
#
# @type Hexarotor x
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_PITCHRATE_P 0.0800
param set-default MC_PITCHRATE_I 0.0400
param set-default MC_PITCHRATE_D 0.0010
param set-default MC_PITCH_P 9.0
param set-default MC_ROLLRATE_P 0.0800
param set-default MC_ROLLRATE_I 0.0400
param set-default MC_ROLLRATE_D 0.0010
param set-default MC_ROLL_P 9.0
param set-default MPC_XY_VEL_I_ACC 4
param set-default MPC_XY_VEL_P_ACC 3
param set-default RTL_DESCEND_ALT 10
param set-default TRIG_INTERFACE 3
param set-default TRIG_MODE 4
param set-default MNT_MODE_IN 4
param set-default MNT_MODE_OUT 2
param set-default MAV_PROTO_VER 2
set MAV_TYPE 13
set MIXER hexa_x
@@ -0,0 +1,10 @@
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530 -p
# shellcheck disable=SC2154
mavlink stream -r 10 -s MOUNT_ORIENTATION -u $udp_gcs_port_local
# shellcheck disable=SC2154
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u $udp_offboard_port_local
mavlink stream -r 10 -s MOUNT_ORIENTATION -u $udp_offboard_port_local
@@ -79,4 +79,6 @@ px4_add_romfs_files(
6011_typhoon_h480.post
6012_typhoon_h480_ctrlalloc
6012_typhoon_h480_ctrlalloc.post
6013_typhoon_h480_airsim
6013_typhoon_h480_airsim.post
)
+1
View File
@@ -149,6 +149,7 @@ set(models
tiltrotor
typhoon_h480
typhoon_h480_ctrlalloc
typhoon_h480_airsim
uuv_bluerov2_heavy
uuv_hippocampus
)