Skip to content

Commit

Permalink
Common: add WINCH_STATUS message (mavlink#1432)
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 authored Aug 3, 2020
1 parent c1dfa87 commit ae6fc8b
Showing 1 changed file with 28 additions and 0 deletions.
28 changes: 28 additions & 0 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4729,6 +4729,21 @@
<description>Unit is sometimes working, sometimes not.</description>
</entry>
</enum>
<enum name="MAV_WINCH_STATUS_FLAG" bitmask="true">
<description>Winch status flags used in WINCH_STATUS</description>
<entry value="1" name="MAV_WINCH_STATUS_HEALTHY">
<description>Winch is healthy</description>
</entry>
<entry value="2" name="MAV_WINCH_STATUS_FULLY_RETRACTED">
<description>Winch thread is fully retracted</description>
</entry>
<entry value="4" name="MAV_WINCH_STATUS_MOVING">
<description>Winch motor is moving</description>
</entry>
<entry value="8" name="MAV_WINCH_STATUS_CLUTCH_ENGAGED">
<description>Winch clutch is engaged allowing motor to move freely</description>
</entry>
</enum>
</enums>
<messages>
<message id="0" name="HEARTBEAT">
Expand Down Expand Up @@ -7094,6 +7109,19 @@
<field type="uint8_t" name="count">Number of wheels reported.</field>
<field type="double[16]" name="distance" units="m">Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.</field>
</message>
<message id="9005" name="WINCH_STATUS">
<wip/>
<!-- This message is work-in-progress and it can therefore change, and should NOT be used in stable production environments -->
<description>Winch status.</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (synced to UNIX time or since system boot).</field>
<field type="float" name="line_length" units="m">Length of line released. NaN if unknown</field>
<field type="float" name="speed" units="m/s">Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown</field>
<field type="float" name="tension" units="kg">Tension on the line. NaN if unknown</field>
<field type="float" name="voltage" units="V">Voltage of the battery supplying the winch. NaN if unknown</field>
<field type="float" name="current" units="A">Current draw from the winch. NaN if unknown</field>
<field type="int16_t" name="temperature" units="degC">Temperature of the motor. INT16_MAX if unknown</field>
<field type="uint32_t" name="status" display="bitmask" enum="MAV_WINCH_STATUS_FLAG">Status flags</field>
</message>
<message id="12900" name="OPEN_DRONE_ID_BASIC_ID">
<wip/>
<!-- This message is work-in-progress and it can therefore change, and should NOT be used in stable production environments -->
Expand Down

0 comments on commit ae6fc8b

Please sign in to comment.