Skip to content

Commit

Permalink
common:ACTUATOR_OUTPUT_STATUS: Clarify is PWM outputs (mavlink#1252)
Browse files Browse the repository at this point in the history
  • Loading branch information
hamishwillee authored Oct 20, 2019
1 parent ba8a5b3 commit 462e8a1
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4059,7 +4059,7 @@
<field type="uint8_t" name="rssi">Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.</field>
</message>
<message id="36" name="SERVO_OUTPUT_RAW">
<description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description>
<description>Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description>
<field type="uint32_t" name="time_usec" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.</field>
<field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.</field>
<field type="uint16_t" name="servo1_raw" units="us">Servo output 1 value</field>
Expand Down Expand Up @@ -5790,7 +5790,7 @@
<field type="uint16_t[16]" name="voltages" units="mV">Individual cell voltages. Batteries with more 16 cells can use the cell_offset field to specify the cell offset for the array specified in the current message . Index values above the valid cell count for this battery should have the UINT16_MAX value.</field>
</message>
<message id="375" name="ACTUATOR_OUTPUT_STATUS">
<description>The raw values of the actuator outputs.</description>
<description>The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW.</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (since system boot).</field>
<field type="uint32_t" name="active" display="bitmask">Active outputs</field>
<field type="float[32]" name="actuator">Servo / motor output array values. Zero values indicate unused channels.</field>
Expand Down

0 comments on commit 462e8a1

Please sign in to comment.