Hello everyone
This topic is to propose the support on Ardupilot of a camera streaming custom MAVLink message.
A few weeks ago @lucasdemarchi presented on the weekly dev call the camera streaming solution that we are developing.
For those who were not able to participate, I will give a brief overview of what it is.
-
There’s a Python Script that will get the cameras from /dev/videoX and create RTP/RTSP streams using gstreamer, its basically a daemon that exports this information to D-BUS.
-
We’ll have a custom MAVLink message that will be used to send/receive information about the streams. (Ardupilot would have to get the information from D-BUS and send whenever needed as MAVLink messages)
-
We’ll add also some new UI on QGroundControl in order to enable changes on streams. (QGroundControl would have to get these changes from UI and send whenever needed as MAVLink messages)
This sequence diagram shows the track of a simple message.
It’s important to notice that the objective of this custom MAVLink message is to provide information about the streams, not to provide the stream data itself.
This video shows a little bit about what has being done, this part is not using the custom MAVLink message yet, everything is running local, https://drive.google.com/open?id=0B2EZFTQdeg3oR2lHQ2N0Sy1YZmc
I would like to ask you guys for a review of what you think of it as well as review the message itself.
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="CAMERA_STREAM_GET_CMD">
<description>Commands to be executed in order to get stream data on "CAMERA_STREAM_GET" message "command" field.</description>
<entry value="1" name="CAMERA_STREAM_GET_CMD_SERVER">
<description>Command to get server attributes</description>
</entry>
<entry value="2" name="CAMERA_STREAM_GET_CMD_STREAMS">
<description>Command to get available streams</description>
</entry>
<entry value="3" name="CAMERA_STREAM_GET_CMD_DATA">
<description>Command to get data of a specific stream</description>
</entry>
</enum>
</enums>
<messages>
<message id="150" name="CAMERA_STREAM_GET">
<description>Message that get stream data using "CAMERA_STREAM_GET_CMD" commands.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="id">Camera device ID</field>
<field type="uint8_t" name="command">CAMERA_STREAM_GET_CMD enum</field>
</message>
<message id="151" name="CAMERA_STREAM_SERVER">
<description>Message that can be requested by sending the "CAMERA_STREAM_GET_CMD_SERVER" command on "CAMERA_STREAM_GET" message.</description>
<field type="char[40]" name="ip">Camera stream server ip to accept connections on the given address</field>
<field type="uint16_t" name="port">Camera stream port which the server will accept connections</field>
</message>
<message id="152" name="SET_CAMERA_STREAM_SERVER">
<description>Message that sets the camera stream server attributes.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="char[40]" name="ip">Camera stream server ip to accept connections on the given address</field>
<field type="uint16_t" name="port">Camera stream port which the server will accept connections</field>
</message>
<message id="153" name="CAMERA_STREAM_STREAM">
<description>Message that returns one stream URI.</description>
<field type="char[60]" name="uri">URI representing the stream</field>
</message>
<message id="154" name="CAMERA_STREAM_DATA">
<description>Message that can be requested by sending the "CAMERA_STREAM_GET_CMD_DATA" command on "CAMERA_STREAM_GET" message.</description>
<field type="uint8_t" name="id">Camera device ID</field>
<field type="uint32_t" name="capabilities">Union of device capabilities flags</field>
<field type="uint32_t" name="format">Camera video format set</field>
<field type="uint32_t[20]" name="available_formats">Camera available video formats</field>
<field type="uint16_t[2]" name="frame_size">Camera video frame size, array followed by width and height</field>
<field type="char[60]" name="uri">Camera stream URI</field>
</message>
<message id="155" name="SET_CAMERA_STREAM_DATA">
<description>Message that sets stream attributes.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="id">Camera device ID</field>
<field type="uint32_t" name="format">Camera video format</field>
<field type="uint16_t[2]" name="frame_size">Camera video frame size, array followed by width and height</field>
<field type="char[30]" name="mount_path">Camera stream mount path to build the URI</field>
</message>
</messages>
</mavlink>
thanks!
–
ricardotk