mirror of https://github.com/ArduPilot/ardupilot
updated XML MAVLink definitions
git-svn-id: https://arducopter.googlecode.com/svn/trunk@3272 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
8b5731fcad
commit
f61aa4d68c
|
@ -35,5 +35,11 @@
|
||||||
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
|
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
|
<message id="152" name="MEMINFO">
|
||||||
|
<description>state of APM memory</description>
|
||||||
|
<field type="uint16_t" name="brkval">heap top</field>
|
||||||
|
<field type="uint16_t" name="freemem">free memory</field>
|
||||||
|
</message>
|
||||||
|
|
||||||
</messages>
|
</messages>
|
||||||
</mavlink>
|
</mavlink>
|
||||||
|
|
|
@ -261,7 +261,6 @@
|
||||||
<param index="6">Empty</param>
|
<param index="6">Empty</param>
|
||||||
<param index="7">Empty</param>
|
<param index="7">Empty</param>
|
||||||
</entry>
|
</entry>
|
||||||
|
|
||||||
<entry value="201" name="MAV_CMD_DO_SET_ROI">
|
<entry value="201" name="MAV_CMD_DO_SET_ROI">
|
||||||
<description>Sets the region of interest (ROI) for a sensor set or the
|
<description>Sets the region of interest (ROI) for a sensor set or the
|
||||||
vehicle itself. This can then be used by the vehicles control
|
vehicle itself. This can then be used by the vehicles control
|
||||||
|
@ -746,7 +745,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
|
||||||
</message>
|
</message>
|
||||||
<message id="57" name="ROLL_PITCH_YAW_THRUST_SETPOINT">
|
<message id="57" name="ROLL_PITCH_YAW_THRUST_SETPOINT">
|
||||||
<description>Setpoint in roll, pitch, yaw currently active on the system.</description>
|
<description>Setpoint in roll, pitch, yaw currently active on the system.</description>
|
||||||
<field type="uint32_t" name="time_ms">Timestamp in milliseconds since system boot</field>
|
<field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field>
|
||||||
<field type="float" name="roll">Desired roll angle in radians</field>
|
<field type="float" name="roll">Desired roll angle in radians</field>
|
||||||
<field type="float" name="pitch">Desired pitch angle in radians</field>
|
<field type="float" name="pitch">Desired pitch angle in radians</field>
|
||||||
<field type="float" name="yaw">Desired yaw angle in radians</field>
|
<field type="float" name="yaw">Desired yaw angle in radians</field>
|
||||||
|
@ -754,7 +753,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
|
||||||
</message>
|
</message>
|
||||||
<message id="58" name="ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT">
|
<message id="58" name="ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT">
|
||||||
<description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description>
|
<description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description>
|
||||||
<field type="uint32_t" name="time_ms">Timestamp in milliseconds since system boot</field>
|
<field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field>
|
||||||
<field type="float" name="roll_speed">Desired roll angular speed in rad/s</field>
|
<field type="float" name="roll_speed">Desired roll angular speed in rad/s</field>
|
||||||
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
|
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
|
||||||
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
|
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
|
||||||
|
@ -825,13 +824,13 @@ of the controller before actual flight and to assist with tuning controller para
|
||||||
</message>
|
</message>
|
||||||
<message id="68" name="HIL_CONTROLS">
|
<message id="68" name="HIL_CONTROLS">
|
||||||
<description>Hardware in the loop control outputs</description>
|
<description>Hardware in the loop control outputs</description>
|
||||||
<field name="time_us" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
|
<field type="uint64_t" name="time_us">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
|
||||||
<field name="roll_ailerons" type="float">Control output -3 .. 1</field>
|
<field type="float" name="roll_ailerons">Control output -3 .. 1</field>
|
||||||
<field name="pitch_elevator" type="float">Control output -1 .. 1</field>
|
<field type="float" name="pitch_elevator">Control output -1 .. 1</field>
|
||||||
<field name="yaw_rudder" type="float">Control output -1 .. 1</field>
|
<field type="float" name="yaw_rudder">Control output -1 .. 1</field>
|
||||||
<field name="throttle" type="float">Throttle 0 .. 1</field>
|
<field type="float" name="throttle">Throttle 0 .. 1</field>
|
||||||
<field name="mode" type="uint8_t">System mode (MAV_MODE)</field>
|
<field type="uint8_t" name="mode">System mode (MAV_MODE)</field>
|
||||||
<field name="nav_mode" type="uint8_t">Navigation mode (MAV_NAV_MODE)</field>
|
<field type="uint8_t" name="nav_mode">Navigation mode (MAV_NAV_MODE)</field>
|
||||||
</message>
|
</message>
|
||||||
<message id="69" name="MANUAL_CONTROL">
|
<message id="69" name="MANUAL_CONTROL">
|
||||||
<field type="uint8_t" name="target">The system to be controlled</field>
|
<field type="uint8_t" name="target">The system to be controlled</field>
|
||||||
|
@ -891,6 +890,25 @@ of the controller before actual flight and to assist with tuning controller para
|
||||||
<field type="float" name="command">Current airspeed in m/s</field>
|
<field type="float" name="command">Current airspeed in m/s</field>
|
||||||
<field type="float" name="result">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field>
|
<field type="float" name="result">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="100" name="OPTICAL_FLOW">
|
||||||
|
<description>Optical flow from a flow sensor (e.g. optical mouse sensor)</description>
|
||||||
|
<field type="uint64_t" name="time">Timestamp (UNIX)</field>
|
||||||
|
<field type="uint8_t" name="sensor_id">Sensor ID</field>
|
||||||
|
<field type="int16_t" name="flow_x">Flow in pixels in x-sensor direction</field>
|
||||||
|
<field type="int16_t" name="flow_y">Flow in pixels in y-sensor direction</field>
|
||||||
|
<field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field>
|
||||||
|
<field type="float" name="ground_distance">Ground distance in meters</field>
|
||||||
|
</message>
|
||||||
|
<message id="140" name="OBJECT_DETECTION_EVENT">
|
||||||
|
<description>Object has been detected</description>
|
||||||
|
<field type="uint32_t" name="time">Timestamp in milliseconds since system boot</field>
|
||||||
|
<field type="uint16_t" name="object_id">Object ID</field>
|
||||||
|
<field type="uint8_t" name="type">Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal</field>
|
||||||
|
<field type="char[20]" name="name">Name of the object as defined by the detector</field>
|
||||||
|
<field type="uint8_t" name="quality">Detection quality / confidence. 0: bad, 255: maximum confidence</field>
|
||||||
|
<field type="float" name="bearing">Angle of the object with respect to the body frame in NED coordinates in radians. 0: front</field>
|
||||||
|
<field type="float" name="distance">Ground distance in meters</field>
|
||||||
|
</message>
|
||||||
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
|
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
|
||||||
<message id="251" name="DEBUG_VECT">
|
<message id="251" name="DEBUG_VECT">
|
||||||
<field type="char[10]" name="name">Name</field>
|
<field type="char[10]" name="name">Name</field>
|
||||||
|
|
|
@ -1,264 +1,227 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version='1.0'?>
|
||||||
<mavlink>
|
<mavlink>
|
||||||
<include>common.xml</include>
|
<include>common.xml</include>
|
||||||
|
|
||||||
<enums>
|
<enums>
|
||||||
<enum name="DATA_TYPES">
|
<enum name="DATA_TYPES">
|
||||||
<description>Content Types for data transmission handshake</description>
|
<description>Content Types for data transmission handshake</description>
|
||||||
<entry name = "DATA_TYPE_JPEG_IMAGE" value="1">
|
<entry value="1" name="DATA_TYPE_JPEG_IMAGE"/>
|
||||||
</entry>
|
<entry value="2" name="DATA_TYPE_RAW_IMAGE"/>
|
||||||
<entry name = "DATA_TYPE_RAW_IMAGE" value="2">
|
<entry value="3" name="DATA_TYPE_KINECT"/>
|
||||||
</entry>
|
|
||||||
<entry name = "DATA_TYPE_KINECT" value="3">
|
|
||||||
</entry>
|
|
||||||
</enum>
|
</enum>
|
||||||
</enums>
|
</enums>
|
||||||
|
|
||||||
<messages>
|
<messages>
|
||||||
<message name="ATTITUDE_CONTROL" id="85">
|
<message id="151" name="SET_CAM_SHUTTER">
|
||||||
<field name="target" type="uint8_t">The system to be controlled</field>
|
<field type="uint8_t" name="cam_no">Camera id</field>
|
||||||
<field name="roll" type="float">roll</field>
|
<field type="uint8_t" name="cam_mode">Camera mode: 0 = auto, 1 = manual</field>
|
||||||
<field name="pitch" type="float">pitch</field>
|
<field type="uint8_t" name="trigger_pin">Trigger pin, 0-3 for PtGrey FireFly</field>
|
||||||
<field name="yaw" type="float">yaw</field>
|
<field type="uint16_t" name="interval">Shutter interval, in microseconds</field>
|
||||||
<field name="thrust" type="float">thrust</field>
|
<field type="uint16_t" name="exposure">Exposure time, in microseconds</field>
|
||||||
<field name="roll_manual" type="uint8_t">roll control enabled auto:0, manual:1</field>
|
<field type="float" name="gain">Camera gain</field>
|
||||||
<field name="pitch_manual" type="uint8_t">pitch auto:0, manual:1</field>
|
|
||||||
<field name="yaw_manual" type="uint8_t">yaw auto:0, manual:1</field>
|
|
||||||
<field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="152" name="IMAGE_TRIGGERED">
|
||||||
<message name="SET_CAM_SHUTTER" id="100">
|
<field type="uint64_t" name="timestamp">Timestamp</field>
|
||||||
<field name="cam_no" type="uint8_t">Camera id</field>
|
<field type="uint32_t" name="seq">IMU seq</field>
|
||||||
<field name="cam_mode" type="uint8_t">Camera mode: 0 = auto, 1 = manual</field>
|
<field type="float" name="roll">Roll angle in rad</field>
|
||||||
<field name="trigger_pin" type="uint8_t">Trigger pin, 0-3 for PtGrey FireFly</field>
|
<field type="float" name="pitch">Pitch angle in rad</field>
|
||||||
<field name="interval" type="uint16_t">Shutter interval, in microseconds</field>
|
<field type="float" name="yaw">Yaw angle in rad</field>
|
||||||
<field name="exposure" type="uint16_t">Exposure time, in microseconds</field>
|
<field type="float" name="local_z">Local frame Z coordinate (height over ground)</field>
|
||||||
<field name="gain" type="float">Camera gain</field>
|
<field type="float" name="lat">GPS X coordinate</field>
|
||||||
|
<field type="float" name="lon">GPS Y coordinate</field>
|
||||||
|
<field type="float" name="alt">Global frame altitude</field>
|
||||||
|
<field type="float" name="ground_x">Ground truth X</field>
|
||||||
|
<field type="float" name="ground_y">Ground truth Y</field>
|
||||||
|
<field type="float" name="ground_z">Ground truth Z</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="153" name="IMAGE_TRIGGER_CONTROL">
|
||||||
<message name="IMAGE_TRIGGERED" id="101">
|
<field type="uint8_t" name="enable">0 to disable, 1 to enable</field>
|
||||||
<field name="timestamp" type="uint64_t">Timestamp</field>
|
|
||||||
<field name="seq" type="uint32_t">IMU seq</field>
|
|
||||||
<field name="roll" type="float">Roll angle in rad</field>
|
|
||||||
<field name="pitch" type="float">Pitch angle in rad</field>
|
|
||||||
<field name="yaw" type="float">Yaw angle in rad</field>
|
|
||||||
<field name="local_z" type="float">Local frame Z coordinate (height over ground)</field>
|
|
||||||
<field name="lat" type="float">GPS X coordinate</field>
|
|
||||||
<field name="lon" type="float">GPS Y coordinate</field>
|
|
||||||
<field name="alt" type="float">Global frame altitude</field>
|
|
||||||
<field name="ground_x" type="float">Ground truth X</field>
|
|
||||||
<field name="ground_y" type="float">Ground truth Y</field>
|
|
||||||
<field name="ground_z" type="float">Ground truth Z</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="154" name="IMAGE_AVAILABLE">
|
||||||
<message name="IMAGE_TRIGGER_CONTROL" id="102">
|
<field type="uint64_t" name="cam_id">Camera id</field>
|
||||||
<field name="enable" type="uint8_t">0 to disable, 1 to enable</field>
|
<field type="uint8_t" name="cam_no">Camera # (starts with 0)</field>
|
||||||
|
<field type="uint64_t" name="timestamp">Timestamp</field>
|
||||||
|
<field type="uint64_t" name="valid_until">Until which timestamp this buffer will stay valid</field>
|
||||||
|
<field type="uint32_t" name="img_seq">The image sequence number</field>
|
||||||
|
<field type="uint32_t" name="img_buf_index">Position of the image in the buffer, starts with 0</field>
|
||||||
|
<field type="uint16_t" name="width">Image width</field>
|
||||||
|
<field type="uint16_t" name="height">Image height</field>
|
||||||
|
<field type="uint16_t" name="depth">Image depth</field>
|
||||||
|
<field type="uint8_t" name="channels">Image channels</field>
|
||||||
|
<field type="uint32_t" name="key">Shared memory area key</field>
|
||||||
|
<field type="uint32_t" name="exposure">Exposure time, in microseconds</field>
|
||||||
|
<field type="float" name="gain">Camera gain</field>
|
||||||
|
<field type="float" name="roll">Roll angle in rad</field>
|
||||||
|
<field type="float" name="pitch">Pitch angle in rad</field>
|
||||||
|
<field type="float" name="yaw">Yaw angle in rad</field>
|
||||||
|
<field type="float" name="local_z">Local frame Z coordinate (height over ground)</field>
|
||||||
|
<field type="float" name="lat">GPS X coordinate</field>
|
||||||
|
<field type="float" name="lon">GPS Y coordinate</field>
|
||||||
|
<field type="float" name="alt">Global frame altitude</field>
|
||||||
|
<field type="float" name="ground_x">Ground truth X</field>
|
||||||
|
<field type="float" name="ground_y">Ground truth Y</field>
|
||||||
|
<field type="float" name="ground_z">Ground truth Z</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="156" name="VISION_POSITION_ESTIMATE">
|
||||||
<message name="IMAGE_AVAILABLE" id="103">
|
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
|
||||||
<field name="cam_id" type="uint64_t">Camera id</field>
|
<field type="float" name="x">Global X position</field>
|
||||||
<field name="cam_no" type="uint8_t">Camera # (starts with 0)</field>
|
<field type="float" name="y">Global Y position</field>
|
||||||
<field name="timestamp" type="uint64_t">Timestamp</field>
|
<field type="float" name="z">Global Z position</field>
|
||||||
<field name="valid_until" type="uint64_t">Until which timestamp this buffer will stay valid</field>
|
<field type="float" name="roll">Roll angle in rad</field>
|
||||||
<field name="img_seq" type="uint32_t">The image sequence number</field>
|
<field type="float" name="pitch">Pitch angle in rad</field>
|
||||||
<field name="img_buf_index" type="uint32_t">Position of the image in the buffer, starts with 0</field>
|
<field type="float" name="yaw">Yaw angle in rad</field>
|
||||||
<field name="width" type="uint16_t">Image width</field>
|
|
||||||
<field name="height" type="uint16_t">Image height</field>
|
|
||||||
<field name="depth" type="uint16_t">Image depth</field>
|
|
||||||
<field name="channels" type="uint8_t">Image channels</field>
|
|
||||||
<field name="key" type="uint32_t">Shared memory area key</field>
|
|
||||||
<field name="exposure" type="uint32_t">Exposure time, in microseconds</field>
|
|
||||||
<field name="gain" type="float">Camera gain</field>
|
|
||||||
<field name="roll" type="float">Roll angle in rad</field>
|
|
||||||
<field name="pitch" type="float">Pitch angle in rad</field>
|
|
||||||
<field name="yaw" type="float">Yaw angle in rad</field>
|
|
||||||
<field name="local_z" type="float">Local frame Z coordinate (height over ground)</field>
|
|
||||||
<field name="lat" type="float">GPS X coordinate</field>
|
|
||||||
<field name="lon" type="float">GPS Y coordinate</field>
|
|
||||||
<field name="alt" type="float">Global frame altitude</field>
|
|
||||||
<field name="ground_x" type="float">Ground truth X</field>
|
|
||||||
<field name="ground_y" type="float">Ground truth Y</field>
|
|
||||||
<field name="ground_z" type="float">Ground truth Z</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="157" name="VICON_POSITION_ESTIMATE">
|
||||||
<message name="VISION_POSITION_ESTIMATE" id="111">
|
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
|
||||||
<field name="usec" type="uint64_t">Timestamp (milliseconds)</field>
|
<field type="float" name="x">Global X position</field>
|
||||||
<field name="x" type="float">Global X position</field>
|
<field type="float" name="y">Global Y position</field>
|
||||||
<field name="y" type="float">Global Y position</field>
|
<field type="float" name="z">Global Z position</field>
|
||||||
<field name="z" type="float">Global Z position</field>
|
<field type="float" name="roll">Roll angle in rad</field>
|
||||||
<field name="roll" type="float">Roll angle in rad</field>
|
<field type="float" name="pitch">Pitch angle in rad</field>
|
||||||
<field name="pitch" type="float">Pitch angle in rad</field>
|
<field type="float" name="yaw">Yaw angle in rad</field>
|
||||||
<field name="yaw" type="float">Yaw angle in rad</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="158" name="VISION_SPEED_ESTIMATE">
|
||||||
<message name="VICON_POSITION_ESTIMATE" id="112">
|
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
|
||||||
<field name="usec" type="uint64_t">Timestamp (milliseconds)</field>
|
<field type="float" name="x">Global X speed</field>
|
||||||
<field name="x" type="float">Global X position</field>
|
<field type="float" name="y">Global Y speed</field>
|
||||||
<field name="y" type="float">Global Y position</field>
|
<field type="float" name="z">Global Z speed</field>
|
||||||
<field name="z" type="float">Global Z position</field>
|
|
||||||
<field name="roll" type="float">Roll angle in rad</field>
|
|
||||||
<field name="pitch" type="float">Pitch angle in rad</field>
|
|
||||||
<field name="yaw" type="float">Yaw angle in rad</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="159" name="POSITION_CONTROL_SETPOINT_SET">
|
||||||
<message name="VISION_SPEED_ESTIMATE" id="113">
|
|
||||||
<field name="usec" type="uint64_t">Timestamp (milliseconds)</field>
|
|
||||||
<field name="x" type="float">Global X speed</field>
|
|
||||||
<field name="y" type="float">Global Y speed</field>
|
|
||||||
<field name="z" type="float">Global Z speed</field>
|
|
||||||
</message>
|
|
||||||
|
|
||||||
<message name="POSITION_CONTROL_SETPOINT_SET" id="120">
|
|
||||||
<description>Message sent to the MAV to set a new position as reference for the controller</description>
|
<description>Message sent to the MAV to set a new position as reference for the controller</description>
|
||||||
<field name="target_system" type="uint8_t">System ID</field>
|
<field type="uint8_t" name="target_system">System ID</field>
|
||||||
<field name="target_component" type="uint8_t">Component ID</field>
|
<field type="uint8_t" name="target_component">Component ID</field>
|
||||||
<field name="id" type="uint16_t">ID of waypoint, 0 for plain position</field>
|
<field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field>
|
||||||
<field name="x" type="float">x position</field>
|
<field type="float" name="x">x position</field>
|
||||||
<field name="y" type="float">y position</field>
|
<field type="float" name="y">y position</field>
|
||||||
<field name="z" type="float">z position</field>
|
<field type="float" name="z">z position</field>
|
||||||
<field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
|
<field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="160" name="POSITION_CONTROL_OFFSET_SET">
|
||||||
<message name="POSITION_CONTROL_OFFSET_SET" id="154">
|
|
||||||
<description>Message sent to the MAV to set a new offset from the currently controlled position</description>
|
<description>Message sent to the MAV to set a new offset from the currently controlled position</description>
|
||||||
<field name="target_system" type="uint8_t">System ID</field>
|
<field type="uint8_t" name="target_system">System ID</field>
|
||||||
<field name="target_component" type="uint8_t">Component ID</field>
|
<field type="uint8_t" name="target_component">Component ID</field>
|
||||||
<field name="x" type="float">x position offset</field>
|
<field type="float" name="x">x position offset</field>
|
||||||
<field name="y" type="float">y position offset</field>
|
<field type="float" name="y">y position offset</field>
|
||||||
<field name="z" type="float">z position offset</field>
|
<field type="float" name="z">z position offset</field>
|
||||||
<field name="yaw" type="float">yaw orientation offset in radians, 0 = NORTH</field>
|
<field type="float" name="yaw">yaw orientation offset in radians, 0 = NORTH</field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<!-- Message sent by the MAV once it sets a new position as reference in the controller -->
|
<!-- Message sent by the MAV once it sets a new position as reference in the controller -->
|
||||||
<message name="POSITION_CONTROL_SETPOINT" id="121">
|
<message id="170" name="POSITION_CONTROL_SETPOINT">
|
||||||
<field name="id" type="uint16_t">ID of waypoint, 0 for plain position</field>
|
<field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field>
|
||||||
<field name="x" type="float">x position</field>
|
<field type="float" name="x">x position</field>
|
||||||
<field name="y" type="float">y position</field>
|
<field type="float" name="y">y position</field>
|
||||||
<field name="z" type="float">z position</field>
|
<field type="float" name="z">z position</field>
|
||||||
<field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
|
<field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="171" name="MARKER">
|
||||||
<message name="MARKER" id="130">
|
<field type="uint16_t" name="id">ID</field>
|
||||||
<field name="id" type="uint16_t">ID</field>
|
<field type="float" name="x">x position</field>
|
||||||
<field name="x" type="float">x position</field>
|
<field type="float" name="y">y position</field>
|
||||||
<field name="y" type="float">y position</field>
|
<field type="float" name="z">z position</field>
|
||||||
<field name="z" type="float">z position</field>
|
<field type="float" name="roll">roll orientation</field>
|
||||||
<field name="roll" type="float">roll orientation</field>
|
<field type="float" name="pitch">pitch orientation</field>
|
||||||
<field name="pitch" type="float">pitch orientation</field>
|
<field type="float" name="yaw">yaw orientation</field>
|
||||||
<field name="yaw" type="float">yaw orientation</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="172" name="RAW_AUX">
|
||||||
<message name="RAW_AUX" id="141">
|
<field type="uint16_t" name="adc1">ADC1 (J405 ADC3, LPC2148 AD0.6)</field>
|
||||||
<field name="adc1" type="uint16_t">ADC1 (J405 ADC3, LPC2148 AD0.6)</field>
|
<field type="uint16_t" name="adc2">ADC2 (J405 ADC5, LPC2148 AD0.2)</field>
|
||||||
<field name="adc2" type="uint16_t">ADC2 (J405 ADC5, LPC2148 AD0.2)</field>
|
<field type="uint16_t" name="adc3">ADC3 (J405 ADC6, LPC2148 AD0.1)</field>
|
||||||
<field name="adc3" type="uint16_t">ADC3 (J405 ADC6, LPC2148 AD0.1)</field>
|
<field type="uint16_t" name="adc4">ADC4 (J405 ADC7, LPC2148 AD1.3)</field>
|
||||||
<field name="adc4" type="uint16_t">ADC4 (J405 ADC7, LPC2148 AD1.3)</field>
|
<field type="uint16_t" name="vbat">Battery voltage</field>
|
||||||
<field name="vbat" type="uint16_t">Battery voltage</field>
|
<field type="int16_t" name="temp">Temperature (degrees celcius)</field>
|
||||||
<field name="temp" type="int16_t">Temperature (degrees celcius)</field>
|
<field type="int32_t" name="baro">Barometric pressure (hecto Pascal)</field>
|
||||||
<field name="baro" type="int32_t">Barometric pressure (hecto Pascal)</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="180" name="WATCHDOG_HEARTBEAT">
|
||||||
<message name="AUX_STATUS" id="142">
|
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
|
||||||
<field name="load" type="uint16_t">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field>
|
<field type="uint16_t" name="process_count">Number of processes</field>
|
||||||
<field name="i2c0_err_count" type="uint16_t">Number of I2C errors since startup</field>
|
|
||||||
<field name="i2c1_err_count" type="uint16_t">Number of I2C errors since startup</field>
|
|
||||||
<field name="spi0_err_count" type="uint16_t">Number of I2C errors since startup</field>
|
|
||||||
<field name="spi1_err_count" type="uint16_t">Number of I2C errors since startup</field>
|
|
||||||
<field name="uart_total_err_count" type="uint16_t">Number of I2C errors since startup</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="181" name="WATCHDOG_PROCESS_INFO">
|
||||||
<message name="WATCHDOG_HEARTBEAT" id="150">
|
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
|
||||||
<field name="watchdog_id" type="uint16_t">Watchdog ID</field>
|
<field type="uint16_t" name="process_id">Process ID</field>
|
||||||
<field name="process_count" type="uint16_t">Number of processes</field>
|
<field type="char[100]" name="name">Process name</field>
|
||||||
|
<field type="char[147]" name="arguments">Process arguments</field>
|
||||||
|
<field type="int32_t" name="timeout">Timeout (seconds)</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="182" name="WATCHDOG_PROCESS_STATUS">
|
||||||
<message name="WATCHDOG_PROCESS_INFO" id="151">
|
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
|
||||||
<field name="watchdog_id" type="uint16_t">Watchdog ID</field>
|
<field type="uint16_t" name="process_id">Process ID</field>
|
||||||
<field name="process_id" type="uint16_t">Process ID</field>
|
<field type="uint8_t" name="state">Is running / finished / suspended / crashed</field>
|
||||||
<field name="name" type="array[100]">Process name</field>
|
<field type="uint8_t" name="muted">Is muted</field>
|
||||||
<field name="arguments" type="array[147]">Process arguments</field>
|
<field type="int32_t" name="pid">PID</field>
|
||||||
<field name="timeout" type="int32_t">Timeout (seconds)</field>
|
<field type="uint16_t" name="crashes">Number of crashes</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="183" name="WATCHDOG_COMMAND">
|
||||||
<message name="WATCHDOG_PROCESS_STATUS" id="152">
|
<field type="uint8_t" name="target_system_id">Target system ID</field>
|
||||||
<field name="watchdog_id" type="uint16_t">Watchdog ID</field>
|
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
|
||||||
<field name="process_id" type="uint16_t">Process ID</field>
|
<field type="uint16_t" name="process_id">Process ID</field>
|
||||||
<field name="state" type="uint8_t">Is running / finished / suspended / crashed</field>
|
<field type="uint8_t" name="command_id">Command ID</field>
|
||||||
<field name="muted" type="uint8_t">Is muted</field>
|
|
||||||
<field name="pid" type="int32_t">PID</field>
|
|
||||||
<field name="crashes" type="uint16_t">Number of crashes</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="190" name="PATTERN_DETECTED">
|
||||||
<message name="WATCHDOG_COMMAND" id="153">
|
<field type="uint8_t" name="type">0: Pattern, 1: Letter</field>
|
||||||
<field name="target_system_id" type="uint8_t">Target system ID</field>
|
<field type="float" name="confidence">Confidence of detection</field>
|
||||||
<field name="watchdog_id" type="uint16_t">Watchdog ID</field>
|
<field type="char[100]" name="file">Pattern file name</field>
|
||||||
<field name="process_id" type="uint16_t">Process ID</field>
|
<field type="uint8_t" name="detected">Accepted as true detection, 0 no, 1 yes</field>
|
||||||
<field name="command_id" type="uint8_t">Command ID</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="191" name="POINT_OF_INTEREST">
|
||||||
<message name="PATTERN_DETECTED" id="160">
|
|
||||||
<field name="type" type="uint8_t">0: Pattern, 1: Letter</field>
|
|
||||||
<field name="confidence" type="float">Confidence of detection</field>
|
|
||||||
<field name="file" type="array[100]">Pattern file name</field>
|
|
||||||
<field name="detected" type="uint8_t">Accepted as true detection, 0 no, 1 yes</field>
|
|
||||||
</message>
|
|
||||||
|
|
||||||
<message name="POINT_OF_INTEREST" id="161">
|
|
||||||
<description>Notifies the operator about a point of interest (POI). This can be anything detected by the
|
<description>Notifies the operator about a point of interest (POI). This can be anything detected by the
|
||||||
system. This generic message is intented to help interfacing to generic visualizations and to display
|
system. This generic message is intented to help interfacing to generic visualizations and to display
|
||||||
the POI on a map.
|
the POI on a map.
|
||||||
</description>
|
</description>
|
||||||
<field name="type" type="uint8_t">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
|
<field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
|
||||||
<field name="color" type="uint8_t">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
|
<field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
|
||||||
<field name="coordinate_system" type="uint8_t">0: global, 1:local</field>
|
<field type="uint8_t" name="coordinate_system">0: global, 1:local</field>
|
||||||
<field name="timeout" type="uint16_t">0: no timeout, >1: timeout in seconds</field>
|
<field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field>
|
||||||
<field name="x" type="float">X Position</field>
|
<field type="float" name="x">X Position</field>
|
||||||
<field name="y" type="float">Y Position</field>
|
<field type="float" name="y">Y Position</field>
|
||||||
<field name="z" type="float">Z Position</field>
|
<field type="float" name="z">Z Position</field>
|
||||||
<field name="name" type="array[25]">POI name</field>
|
<field type="char[26]" name="name">POI name</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="192" name="POINT_OF_INTEREST_CONNECTION">
|
||||||
<message name="POINT_OF_INTEREST_CONNECTION" id="162">
|
|
||||||
<description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the
|
<description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the
|
||||||
system. This generic message is intented to help interfacing to generic visualizations and to display
|
system. This generic message is intented to help interfacing to generic visualizations and to display
|
||||||
the POI on a map.
|
the POI on a map.
|
||||||
</description>
|
</description>
|
||||||
<field name="type" type="uint8_t">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
|
<field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
|
||||||
<field name="color" type="uint8_t">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
|
<field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
|
||||||
<field name="coordinate_system" type="uint8_t">0: global, 1:local</field>
|
<field type="uint8_t" name="coordinate_system">0: global, 1:local</field>
|
||||||
<field name="timeout" type="uint16_t">0: no timeout, >1: timeout in seconds</field>
|
<field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field>
|
||||||
<field name="xp1" type="float">X1 Position</field>
|
<field type="float" name="xp1">X1 Position</field>
|
||||||
<field name="yp1" type="float">Y1 Position</field>
|
<field type="float" name="yp1">Y1 Position</field>
|
||||||
<field name="zp1" type="float">Z1 Position</field>
|
<field type="float" name="zp1">Z1 Position</field>
|
||||||
<field name="xp2" type="float">X2 Position</field>
|
<field type="float" name="xp2">X2 Position</field>
|
||||||
<field name="yp2" type="float">Y2 Position</field>
|
<field type="float" name="yp2">Y2 Position</field>
|
||||||
<field name="zp2" type="float">Z2 Position</field>
|
<field type="float" name="zp2">Z2 Position</field>
|
||||||
<field name="name" type="array[25]">POI connection name</field>
|
<field type="char[26]" name="name">POI connection name</field>
|
||||||
</message>
|
</message>
|
||||||
|
<message id="193" name="DATA_TRANSMISSION_HANDSHAKE">
|
||||||
<message name="DATA_TRANSMISSION_HANDSHAKE" id="170">
|
<field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
|
||||||
<field name="type" type="uint8_t">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
|
<field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field>
|
||||||
<field name="size" type="uint32_t">total data size in bytes (set on ACK only)</field>
|
<field type="uint8_t" name="packets">number of packets beeing sent (set on ACK only)</field>
|
||||||
<field name="packets" type="uint8_t">number of packets beeing sent (set on ACK only)</field>
|
<field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
|
||||||
<field name="payload" type="uint8_t">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
|
<field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field>
|
||||||
<field name="jpg_quality" type="uint8_t">JPEG quality out of [1,100]</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="194" name="ENCAPSULATED_DATA">
|
||||||
<message name="ENCAPSULATED_DATA" id="171">
|
<field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field>
|
||||||
<field name="seqnr" type="uint16_t">sequence number (starting with 0 on every transmission)</field>
|
<field type="uint8_t[253]" name="data">image data bytes</field>
|
||||||
<field name="data" type="uint8_t[253]">image data bytes</field>
|
|
||||||
</message>
|
</message>
|
||||||
|
<message id="195" name="BRIEF_FEATURE">
|
||||||
<message name="BRIEF_FEATURE" id="172">
|
<field type="float" name="x">x position in m</field>
|
||||||
<field name="x" type="float">x position in m</field>
|
<field type="float" name="y">y position in m</field>
|
||||||
<field name="y" type="float">y position in m</field>
|
<field type="float" name="z">z position in m</field>
|
||||||
<field name="z" type="float">z position in m</field>
|
<field type="uint8_t" name="orientation_assignment">Orientation assignment 0: false, 1:true</field>
|
||||||
<field name="orientation_assignment" type="uint8_t">Orientation assignment 0: false, 1:true</field>
|
<field type="uint16_t" name="size">Size in pixels</field>
|
||||||
<field name="size" type="uint16_t">Size in pixels</field>
|
<field type="uint16_t" name="orientation">Orientation</field>
|
||||||
<field name="orientation" type="uint16_t">Orientation</field>
|
<field type="uint8_t[32]" name="descriptor">Descriptor</field>
|
||||||
<field name="descriptor" type="uint8_t[32]">Descriptor</field>
|
<field type="float" name="response">Harris operator response at this location</field>
|
||||||
<field name="response" type="float">Harris operator response at this location</field>
|
</message>
|
||||||
|
<message id="200" name="ATTITUDE_CONTROL">
|
||||||
|
<field type="uint8_t" name="target">The system to be controlled</field>
|
||||||
|
<field type="float" name="roll">roll</field>
|
||||||
|
<field type="float" name="pitch">pitch</field>
|
||||||
|
<field type="float" name="yaw">yaw</field>
|
||||||
|
<field type="float" name="thrust">thrust</field>
|
||||||
|
<field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field>
|
||||||
|
<field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field>
|
||||||
|
<field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field>
|
||||||
|
<field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
</messages>
|
</messages>
|
||||||
</mavlink>
|
</mavlink>
|
||||||
|
|
Loading…
Reference in New Issue