<!-- RALLY flags - power of 2 (1,2,4,8,16,32,64,128) so we can send as a bitfield -->
<enumname="RALLY_FLAGS">
<description>Flags in RALLY_POINT message</description>
<entryname="FAVORABLE_WIND"value="1"><description>Flag set when requiring favorable winds for landing. </description></entry>
<entryname="LAND_IMMEDIATELY"value="2"><description>Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land.</description></entry>
<entryname="CLOSEDLOOP"value="3"><description>Closed loop feedback from camera, we know for sure it has successfully taken a picture</description></entry>
<entryname="OPENLOOP"value="4"><description>Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture</description></entry>
<fieldname="mode"type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field>
<fieldname="shutter_speed"type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field>
<fieldname="aperture"type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field>
<fieldname="iso"type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
<fieldname="exposure_type"type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
<fieldname="command_id"type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<fieldname="session"type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field>
<fieldname="zoom_pos"type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field>
<fieldname="zoom_step"type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field>
<fieldname="focus_lock"type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
<fieldname="shot"type="uint8_t">0: ignore, 1: shot or start filming</field>
<fieldname="command_id"type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<fieldname="extra_param"type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<fieldname="extra_value"type="float">Correspondent value to given extra_param</field>
</message>
<!-- Camera Mount Messages -->
<messagename="MOUNT_CONFIGURE"id="156">
<description>Message to configure a camera mount, directional antenna, etc.</description>
<fieldname="idx"type="uint8_t">point index (first point is 0)</field>
<fieldname="count"type="uint8_t">total number of points (for sanity checking)</field>
<fieldname="lat"type="int32_t">Latitude of point in degrees * 1E7</field>
<fieldname="lng"type="int32_t">Longitude of point in degrees * 1E7</field>
<fieldname="alt"type="int16_t">Transit / loiter altitude in meters relative to home</field>
<!-- Path planned landings are still in the future, but we want these fields ready: -->
<fieldname="break_alt"type="int16_t">Break altitude in meters relative to home</field>
<fieldname="land_dir"type="uint16_t">Heading to aim for when landing. In centi-degrees.</field>
<fieldname="flags"type="uint8_t">See RALLY_FLAGS enum for definition of the bitmask.</field>
</message>
<messagename="RALLY_FETCH_POINT"id="176">
<description>Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.</description>
<!-- camera event message from CCB to autopilot: most obviously for image trigger events but also things like error, low power, full card, etc -->
<messagename="CAMERA_EVENT"id="179">
<description>Camera Event</description>
<fieldname="time_usec"type="uint64_t">Image timestamp (microseconds since UNIX epoch, according to camera clock)</field>
<fieldname="target_system"type="uint8_t">System ID</field><!-- support multiple concurrent vehicles -->
<fieldname="cam_idx"type="uint8_t">Camera ID</field><!-- component ID, to support multiple cameras -->
<fieldname="img_idx"type="uint16_t">Image index</field><!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
<fieldname="event_id"type="uint8_t">See CAMERA_EVENT_TYPES enum for definition of the bitmask</field>
<fieldname="p1"type="float">Parameter 1 (meaning depends on event, see CAMERA_EVENT_TYPES enum)</field>
<fieldname="p2"type="float">Parameter 2 (meaning depends on event, see CAMERA_EVENT_TYPES enum)</field>
<fieldname="p3"type="float">Parameter 3 (meaning depends on event, see CAMERA_EVENT_TYPES enum)</field>
<fieldname="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 -->
<fieldname="time_usec"type="uint64_t">Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_EVENT message</field>
<fieldname="target_system"type="uint8_t">System ID</field><!-- support multiple concurrent vehicles -->
<fieldname="cam_idx"type="uint8_t">Camera ID</field><!-- component ID, to support multiple cameras -->
<fieldname="img_idx"type="uint16_t">Image index</field><!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
<fieldname="lat"type="int32_t">Latitude in (deg * 1E7)</field>
<fieldname="lng"type="int32_t">Longitude in (deg * 1E7)</field>
<fieldname="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 -->
<fieldname="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 -->
<fieldname="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 -->
<fieldname="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 -->
<fieldname="flags"type="uint8_t">See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask</field><!-- future proofing -->