mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: added VFWD_THR_OVERRIDE
This commit is contained in:
parent
9c7c995185
commit
936d6ed378
|
@ -228,6 +228,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
||||||
// @Values{Copter, Rover, Plane}: 165:Arm/Emergency Motor Stop
|
// @Values{Copter, Rover, Plane}: 165:Arm/Emergency Motor Stop
|
||||||
// @Values{Copter, Rover, Plane, Blimp}: 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus
|
// @Values{Copter, Rover, Plane, Blimp}: 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus
|
||||||
// @Values{Plane}: 170:QSTABILIZE Mode
|
// @Values{Plane}: 170:QSTABILIZE Mode
|
||||||
|
// @Values{Plane}: 176:Quadplane Fwd Throttle Override enable
|
||||||
// @Values{Copter, Rover, Plane, Blimp}: 171:Calibrate Compasses
|
// @Values{Copter, Rover, Plane, Blimp}: 171:Calibrate Compasses
|
||||||
// @Values{Copter, Rover, Plane, Blimp}: 172:Battery MPPT Enable
|
// @Values{Copter, Rover, Plane, Blimp}: 172:Battery MPPT Enable
|
||||||
// @Values{Plane}: 173:Plane AUTO Mode Landing Abort
|
// @Values{Plane}: 173:Plane AUTO Mode Landing Abort
|
||||||
|
|
|
@ -248,6 +248,7 @@ public:
|
||||||
PLANE_AUTO_LANDING_ABORT = 173, // Abort Glide-slope or VTOL landing during payload place or do_land type mission items
|
PLANE_AUTO_LANDING_ABORT = 173, // Abort Glide-slope or VTOL landing during payload place or do_land type mission items
|
||||||
CAMERA_IMAGE_TRACKING = 174, // camera image tracking
|
CAMERA_IMAGE_TRACKING = 174, // camera image tracking
|
||||||
CAMERA_LENS = 175, // camera lens selection
|
CAMERA_LENS = 175, // camera lens selection
|
||||||
|
VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method
|
||||||
|
|
||||||
|
|
||||||
// inputs from 200 will eventually used to replace RCMAP
|
// inputs from 200 will eventually used to replace RCMAP
|
||||||
|
|
Loading…
Reference in New Issue