diff --git a/text/0015-mavlink_manual_control_update.md b/text/0015-mavlink_manual_control_update.md new file mode 100644 index 0000000..62a4d2e --- /dev/null +++ b/text/0015-mavlink_manual_control_update.md @@ -0,0 +1,40 @@ + * Start date: 2019-05-28 + * Contributors: Mike Lyons , Swift Engineering, Inc. + * Related issues: + +# Summary + +Proposal to extend the manual_control MAVLink message for extra channels. + +# Motivation + +Many autonomous vehicles could benefit from the addition of extra control channels for various functions. In addition, many joystick controllers have additional axes that are currently not used. + +This provides a generic extension to the manual_control message that developers can use and may be used in a more abstract context from using the RC_OVERRIDE message. + +# Detailed Design + +The message contains additional *extension* fields for joystick axis values normalized between -1000 to 1000 for the following channels +* Channel 5 +* Channel 6 +* Channel 7 +* Channel 8 + +## Proposed message extension + +```xml + + 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 + The system to be controlled. + 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. + 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. + 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. Positive values are positive thrust, negative values are negative thrust. + 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. + A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + + axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Corresponds to movement on joystick channel 5 + axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Corresponds to movement on joystick channel 6 + axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Corresponds to movement on joystick channel 7 + axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Corresponds to movement on joystick channel 8 + +``` \ No newline at end of file