From 2837870733a32bdf025a60818861cf4e5cfed983 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 13 Oct 2017 09:57:02 -0400 Subject: [PATCH] posix-configs: send gimbal attitude to mavros port The gimbal attitude is required by DroneCore. --- posix-configs/SITL/init/ekf2/typhoon_h480 | 1 + 1 file changed, 1 insertion(+) diff --git a/posix-configs/SITL/init/ekf2/typhoon_h480 b/posix-configs/SITL/init/ekf2/typhoon_h480 index 9ab235086d..7573b5455b 100644 --- a/posix-configs/SITL/init/ekf2/typhoon_h480 +++ b/posix-configs/SITL/init/ekf2/typhoon_h480 @@ -79,6 +79,7 @@ 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 mavlink stream -r 10 -s MOUNT_ORIENTATION -u 14556 +mavlink stream -r 10 -s MOUNT_ORIENTATION -u 14557 logger start -e -t vmount start camera_trigger start