Skip to content

Commit

Permalink
Merge pull request mavlink#64 from Susurrus/manual_control
Browse files Browse the repository at this point in the history
Altered MANUAL_CONTROL message (number 69) so that it's more generic.
  • Loading branch information
LorenzMeier committed Sep 5, 2012
2 parents 358ad99 + b371e29 commit 89c3ba2
Showing 1 changed file with 7 additions and 9 deletions.
16 changes: 7 additions & 9 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -1362,15 +1362,13 @@
<field type="uint8_t" name="on_off">1 stream is enabled, 0 stream is stopped.</field>
</message>
<message id="69" name="MANUAL_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>
<description>This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their </description>
<field type="uint8_t" name="target">The system to be controlled.</field>
<field type="int16_t" name="x">X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.</field>
<field type="int16_t" name="y">Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.</field>
<field type="int16_t" name="z">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.</field>
<field type="int16_t" name="r">R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.</field>
<field type="uint16_t" name="buttons">A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.</field>
</message>
<message id="70" name="RC_CHANNELS_OVERRIDE">
<description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
Expand Down

0 comments on commit 89c3ba2

Please sign in to comment.