mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
RC_Channel: add ICEngine start / stop aux function
This commit is contained in:
parent
eee2d2f57e
commit
51963f497b
@ -239,6 +239,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
|||||||
// @Values{Plane}: 176:Quadplane Fwd Throttle Override enable
|
// @Values{Plane}: 176:Quadplane Fwd Throttle Override enable
|
||||||
// @Values{Copter, Rover, Plane, Blimp}: 177:Mount LRF enable
|
// @Values{Copter, Rover, Plane, Blimp}: 177:Mount LRF enable
|
||||||
// @Values{Copter}: 178:FlightMode Pause/Resume
|
// @Values{Copter}: 178:FlightMode Pause/Resume
|
||||||
|
// @Values{Plane}: 179:ICEngine start / stop
|
||||||
// @Values{Copter, Plane}: 180:Test autotuned gains after tune is complete
|
// @Values{Copter, Plane}: 180:Test autotuned gains after tune is complete
|
||||||
// @Values{Rover}: 201:Roll
|
// @Values{Rover}: 201:Roll
|
||||||
// @Values{Rover}: 202:Pitch
|
// @Values{Rover}: 202:Pitch
|
||||||
|
@ -252,6 +252,7 @@ public:
|
|||||||
VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method
|
VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method
|
||||||
MOUNT_LRF_ENABLE = 177, // mount LRF enable/disable
|
MOUNT_LRF_ENABLE = 177, // mount LRF enable/disable
|
||||||
FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint
|
FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint
|
||||||
|
ICE_START_STOP = 179, // AP_ICEngine start stop
|
||||||
AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains
|
AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user