forked from Archive/PX4-Autopilot
MAVLink receiver: Clean up joystick interface
This commit is contained in:
parent
3a2e2ef304
commit
6e9a460c17
|
@ -990,8 +990,8 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
|
|||
switch_pos_t
|
||||
MavlinkReceiver::decode_switch_pos(uint16_t buttons, unsigned sw)
|
||||
{
|
||||
// XXX non-standard 3 pos switch decoding
|
||||
return (buttons >> (sw * 2)) & 3;
|
||||
// This 2-bit method should be used in the future: (buttons >> (sw * 2)) & 3;
|
||||
return (buttons & (1 << sw));
|
||||
}
|
||||
|
||||
int
|
||||
|
@ -1101,26 +1101,10 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
|
|||
rc.values[0] = man.x / 2 + 1500;
|
||||
/* pitch */
|
||||
rc.values[1] = man.y / 2 + 1500;
|
||||
|
||||
/*
|
||||
* yaw needs special handling as some joysticks have a circular mechanical mask,
|
||||
* which makes the corner positions unreachable.
|
||||
* scale yaw up and clip it to overcome this.
|
||||
*/
|
||||
rc.values[2] = man.r / 1.1f + 1500;
|
||||
if (rc.values[2] > 2000) {
|
||||
rc.values[2] = 2000;
|
||||
} else if (rc.values[2] < 1000) {
|
||||
rc.values[2] = 1000;
|
||||
}
|
||||
|
||||
/* yaw */
|
||||
rc.values[2] = man.r / 2 + 1500;
|
||||
/* throttle */
|
||||
rc.values[3] = man.z / 0.9f + 1000;
|
||||
if (rc.values[3] > 2000) {
|
||||
rc.values[3] = 2000;
|
||||
} else if (rc.values[3] < 1000) {
|
||||
rc.values[3] = 1000;
|
||||
}
|
||||
rc.values[3] = man.z / 2 + 1000;
|
||||
|
||||
/* decode all switches which fit into the channel mask */
|
||||
unsigned max_switch = (sizeof(man.buttons) * 8);
|
||||
|
|
Loading…
Reference in New Issue