GCS_MAVLink: camera feedback mavlink messages

CAMERA_EVENT and CAMERA_FEEDBACK messages, and a couple of enums they
use (CAMERA_EVENT_TYPES and CAMERA_FEEDBACK_FLAGS)

Adjusted some types and added more explicit descriptions of units as
suggested on the call last week.

I will add camera parameter list/get/set functionality as suggested
using the existing parameter mechanism and component IDs rather than
the new CAMERA_INFO messages I had proposed.
This commit is contained in:
Andrew Chapman 2014-06-17 20:15:20 +10:00 committed by Andrew Tridgell
parent ac65119cfe
commit 048767e389

View File

@ -75,6 +75,23 @@
</entry>
</enum>
<!-- Camera event types -->
<enum name="CAMERA_EVENT_TYPES">
<entry name="HEARTBEAT" value="0"><description>Camera heartbeat, announce camera component ID at 1hz</description></entry>
<entry name="TRIGGER" value="1"><description>Camera image triggered</description></entry>
<entry name="DISCONNECT" value="2"><description>Camera connection lost</description></entry>
<entry name="ERROR" value="3"><description>Camera unknown error</description></entry>
<entry name="LOWBATT" value="4"><description>Camera battery low. Parameter p1 shows reported voltage</description></entry>
<entry name="LOWSTORE" value="5"><description>Camera storage low. Parameter p1 shows reported shots remaining</description></entry>
<entry name="LOWSTOREV" value="6"><description>Camera storage low. Parameter p1 shows reported video minutes remaining</description></entry>
</enum>
<!-- camera feedback flags, a little bit of future-proofing -->
<enum name="CAMERA_FEEDBACK_FLAGS">
<entry name="VIDEO" value="1"> <description>Shooting video, not stills</description></entry>
<entry name="BADEXPOSURE" value="2"> <description>Unable to achieve requested exposure (e.g. shutter speed too low)</description></entry>
</enum>
</enums>
<messages>
@ -386,5 +403,37 @@
<field type="int32_t" name="lat">Latitude in degrees * 1E7</field>
<field type="int32_t" name="lng">Longitude in degrees * 1E7</field>
</message>
<!-- camera event message from CCB to autopilot: most obviously for image trigger events but also things like error, low power, full card, etc -->
<message name="CAMERA_EVENT" id="179">
<description>Camera Event</description>
<field name="time_usec" type="uint64_t">Image timestamp (microseconds since UNIX epoch, according to camera clock)</field>
<field name="target_system" type="uint8_t" >System ID</field> <!-- support multiple concurrent vehicles -->
<field name="cam_idx" type="uint8_t" >Camera ID</field> <!-- component ID, to support multiple cameras -->
<field name="img_idx" type="uint16_t" >Image index</field> <!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
<field name="event_id" type="uint8_t" >See CAMERA_EVENT_TYPES enum for definition of the bitmask</field>
<field name="p1" type="float" >Parameter 1 (meaning depends on event, see CAMERA_EVENT_TYPES enum)</field>
<field name="p2" type="float" >Parameter 2 (meaning depends on event, see CAMERA_EVENT_TYPES enum)</field>
<field name="p3" type="float" >Parameter 3 (meaning depends on event, see CAMERA_EVENT_TYPES enum)</field>
<field name="p4" type="float" >Parameter 4 (meaning depends on event, see CAMERA_EVENT_TYPES enum)</field>
</message>
<!-- camera feedback message from autopilot to both CCB and GCS in response to a CAMERA_EVENT trigger -->
<message name="CAMERA_FEEDBACK" id="180">
<description>Camera Capture Feedback</description>
<field name="time_usec" type="uint64_t">Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_EVENT message</field>
<field name="target_system" type="uint8_t" >System ID</field> <!-- support multiple concurrent vehicles -->
<field name="cam_idx" type="uint8_t" >Camera ID</field> <!-- component ID, to support multiple cameras -->
<field name="img_idx" type="uint16_t">Image index</field> <!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
<field name="lat" type="int32_t" >Latitude in (deg * 1E7)</field>
<field name="lng" type="int32_t" >Longitude in (deg * 1E7)</field>
<field name="alt" type="float" >Altitude (meters, AMSL)</field>
<field name="roll" type="float" >Vehicle Roll angle (degrees, +-180)</field> <!-- gimbal or fixed cam offsets to be handled by GCS, possibly with gimbal state messages later -->
<field name="pitch" type="float" >Vehicle Pitch angle (degrees, +-180)</field> <!-- gimbal or fixed cam offsets to be handled by GCS, possibly with gimbal state messages later -->
<field name="yaw" type="float" >Vehicle Heading (degrees, 0-360, true)</field> <!-- gimbal or fixed cam offsets to be handled by GCS, possibly with gimbal state messages later -->
<field name="foc_len" type="float" >Focal Length (mm)</field> <!-- per-image to support zooms. Zero means fixed focal length or unknown. Should be true mm, not scaled to 35mm film equivalent -->
<field name="flags" type="uint8_t" >See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask</field> <!-- future proofing -->
</message>
</messages>
</mavlink>