mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: use RC channel options 203 and 204 for throttle and yaw
This gives us a 200 + n mapping for the traditional AETR mapping. Unfortunately, it will break walking robots until they update their parameters
This commit is contained in:
parent
7480a2a00b
commit
a97786c01d
|
@ -208,11 +208,13 @@ public:
|
||||||
// inputs from 200 will eventually used to replace RCMAP
|
// inputs from 200 will eventually used to replace RCMAP
|
||||||
ROLL = 201, // roll input
|
ROLL = 201, // roll input
|
||||||
PITCH = 202, // pitch input
|
PITCH = 202, // pitch input
|
||||||
WALKING_HEIGHT = 203, // walking robot height input
|
THROTTLE = 203, // throttle pilot input
|
||||||
|
YAW = 204, // yaw pilot input
|
||||||
MAINSAIL = 207, // mainsail input
|
MAINSAIL = 207, // mainsail input
|
||||||
FLAP = 208, // flap input
|
FLAP = 208, // flap input
|
||||||
FWD_THR = 209, // VTOL manual forward throttle
|
FWD_THR = 209, // VTOL manual forward throttle
|
||||||
AIRBRAKE = 210, // manual airbrake control
|
AIRBRAKE = 210, // manual airbrake control
|
||||||
|
WALKING_HEIGHT = 211, // walking robot height input
|
||||||
|
|
||||||
// inputs for the use of onboard lua scripting
|
// inputs for the use of onboard lua scripting
|
||||||
SCRIPTING_1 = 300,
|
SCRIPTING_1 = 300,
|
||||||
|
|
Loading…
Reference in New Issue