forked from Archive/PX4-Autopilot
mavlink streams: add gimbal orientation feedback to normal stream
It only publishes when the information is available on uORB and is useful for the groundstation to show the gimbal's status.
This commit is contained in:
parent
b0df7c7ccb
commit
938be68c69
|
@ -1425,6 +1425,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
|||
configure_stream_local("HOME_POSITION", 0.5f);
|
||||
configure_stream_local("HYGROMETER_SENSOR", 0.1f);
|
||||
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
|
||||
configure_stream_local("MOUNT_ORIENTATION", 10.0f);
|
||||
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.0f);
|
||||
configure_stream_local("OBSTACLE_DISTANCE", 1.0f);
|
||||
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
|
||||
|
|
Loading…
Reference in New Issue