RC_Channel: add option to flight mode pause/resume via aux function

This commit is contained in:
Peter Barker 2024-04-10 16:01:13 +10:00 committed by Peter Barker
parent 74e7132bd3
commit 468158e0f9
2 changed files with 2 additions and 0 deletions

View File

@ -237,6 +237,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
// @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens // @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens
// @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{Rover}: 201:Roll // @Values{Rover}: 201:Roll
// @Values{Rover}: 202:Pitch // @Values{Rover}: 202:Pitch
// @Values{Rover}: 207:MainSail // @Values{Rover}: 207:MainSail

View File

@ -250,6 +250,7 @@ public:
CAMERA_LENS = 175, // camera lens selection CAMERA_LENS = 175, // camera lens selection
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
// inputs from 200 will eventually used to replace RCMAP // inputs from 200 will eventually used to replace RCMAP