GCS_MAVLink: merge upstream mavlink changes

This commit is contained in:
Andrew Tridgell 2015-02-11 20:13:27 +11:00
parent d0075c0d23
commit b227f8463f
3 changed files with 64 additions and 14 deletions

View File

@ -77,5 +77,31 @@
<field type="float" name="Motor_rpm"> Motor RPM </field>
<!-- to be extended-->
</message>
<message id="206" name="EKF_EXT">
<description>Extended EKF state estimates for ASLUAVs</description>
<field type="uint64_t" name="timestamp"> Time since system start [us]</field>
<field type="float" name="Windspeed"> Magnitude of wind velocity (in lateral inertial plane) [m/s]</field>
<field type="float" name="WindDir"> Wind heading angle from North [rad]</field>
<field type="float" name="WindZ"> Z (Down) component of inertial wind velocity [m/s]</field>
<field type="float" name="Airspeed"> Magnitude of air velocity [m/s]</field>
<field type="float" name="beta"> Sideslip angle [rad]</field>
<field type="float" name="alpha"> Angle of attack [rad]</field>
</message>
<message id="207" name="ASL_OBCTRL">
<description>Off-board controls/commands for ASLUAVs</description>
<field type="uint64_t" name="timestamp"> Time since system start [us]</field>
<field type="float" name="uElev"> Elevator command [~]</field>
<field type="float" name="uThrot"> Throttle command [~]</field>
<field type="float" name="uThrot2"> Throttle 2 command [~]</field>
<field type="float" name="uAilL"> Left aileron command [~]</field>
<field type="float" name="uAilR"> Right aileron command [~]</field>
<field type="float" name="uRud"> Rudder command [~]</field>
<field type="uint8_t" name="obctrl_status"> Off-board computer status</field>
</message>
<message id="208" name="SENS_ATMOS">
<description>Atmospheric sensors (temperature, humidity, ...) </description>
<field type="float" name="TempAmbient"> Ambient temperature [degrees Celsius]</field>
<field type="float" name="Humidity"> Relative humidity [%]</field>
</message>
</messages>
</mavlink>

View File

@ -478,7 +478,7 @@
<field type="float" name="v3">test variable3</field>
<field type="float" name="v4">test variable4</field>
</message>
<message name="AUTOPILOT_VERSION_REQUEST" id="183">
<description>Request the autopilot version from the system/component.</description>
<field type="uint8_t" name="target_system">System ID</field>
@ -486,7 +486,7 @@
</message>
<message name="GIMBAL_REPORT" id="184">
<description>Report from MAVLink enabled gimbal to vehicle</description>
<description>Report from MAVLink enabled gimbal to vehicle. The deltas are in gimbal sensor frame. Joint measurements assume a 312 ordering (azimuth, roll, pitch).</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="delta_time">Time since last update (seconds)</field>
@ -502,7 +502,7 @@
</message>
<message name="GIMBAL_CONTROL" id="185">
<description>Control packet from vehicle to MAVLink enabled gimbal</description>
<description>Control packet from vehicle to MAVLink enabled gimbal. All values in gimbal sensor frame</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="demanded_rate_x">Demanded angular rate X, radians/s</field>

View File

@ -1411,6 +1411,9 @@
<entry value="512" name="MAV_PROTOCOL_CAPABILITY_TERRAIN">
<description>Autopilot supports terrain protocol / data handling.</description>
</entry>
<entry value="1024" name="MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET">
<description>Autopilot supports direct actuator control.</description>
</entry>
</enum>
<enum name="MAV_ESTIMATOR_TYPE">
<description>Enumeration of estimator types</description>
@ -2280,17 +2283,16 @@
<field type="float" name="vd">True velocity in m/s in DOWN direction in earth-fixed NED frame</field>
</message>
<message name="RADIO_STATUS" id="109">
<description>Status generated by radio</description>
<field type="uint8_t" name="rssi">local signal strength</field>
<field type="uint8_t" name="remrssi">remote signal strength</field>
<field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
<field type="uint8_t" name="noise">background noise level</field>
<field type="uint8_t" name="remnoise">remote background noise level</field>
<field type="uint16_t" name="rxerrors">receive errors</field>
<field type="uint16_t" name="fixed">count of error corrected packets</field>
</message>
<message name="RADIO_STATUS" id="109">
<description>Status generated by radio and injected into MAVLink stream.</description>
<field type="uint8_t" name="rssi">Local signal strength</field>
<field type="uint8_t" name="remrssi">Remote signal strength</field>
<field type="uint8_t" name="txbuf">Remaining free buffer space in percent.</field>
<field type="uint8_t" name="noise">Background noise level</field>
<field type="uint8_t" name="remnoise">Remote background noise level</field>
<field type="uint16_t" name="rxerrors">Receive errors</field>
<field type="uint16_t" name="fixed">Count of error corrected packets</field>
</message>
<message id="110" name="FILE_TRANSFER_PROTOCOL">
<description>File transfer message</description>
<field type="uint8_t" name="target_network">Network ID (0 for broadcast)</field>
@ -2536,6 +2538,28 @@
<field type="float" name="press_diff">Differential pressure 1 (hectopascal)</field>
<field type="int16_t" name="temperature">Temperature measurement (0.01 degrees celsius)</field>
</message>
<message id="138" name="ATT_POS_MOCAP">
<description>Motion capture attitude and position</description>
<field type="uint64_t" name="time_usec">Timestamp (micros since boot or Unix epoch)</field>
<field type="float[4]" name="q">Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
<field type="float" name="x">X position in meters (NED)</field>
<field type="float" name="y">Y position in meters (NED)</field>
<field type="float" name="z">Z position in meters (NED)</field>
</message>
<message id="139" name="SET_ACTUATOR_CONTROL_TARGET">
<description>Set the vehicle attitude and body angular rates.</description>
<field type="uint64_t" name="time_usec">Timestamp (micros since boot or Unix epoch)</field>
<field type="uint8_t" name="group_mlx">Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.</field>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float[8]" name="controls">Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.</field>
</message>
<message id="140" name="ACTUATOR_CONTROL_TARGET">
<description>Set the vehicle attitude and body angular rates.</description>
<field type="uint64_t" name="time_usec">Timestamp (micros since boot or Unix epoch)</field>
<field type="uint8_t" name="group_mlx">Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.</field>
<field type="float[8]" name="controls">Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.</field>
</message>
<message id="147" name="BATTERY_STATUS">
<description>Battery information</description>
<field type="uint8_t" name="id">Battery ID</field>