posix-configs: send gimbal attitude to mavros port

The gimbal attitude is required by DroneCore.
This commit is contained in:
Julian Oes 2017-10-13 09:57:02 -04:00 committed by Beat Küng
parent 1e91b8cd32
commit 2837870733
1 changed files with 1 additions and 0 deletions

View File

@ -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