From 468158e0f934827ca3fb2e7e89dae83bfdca98ea Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Apr 2024 16:01:13 +1000 Subject: [PATCH] RC_Channel: add option to flight mode pause/resume via aux function --- libraries/RC_Channel/RC_Channel.cpp | 1 + libraries/RC_Channel/RC_Channel.h | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index a24daf0357..a351463b27 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -237,6 +237,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens // @Values{Plane}: 176:Quadplane Fwd Throttle Override enable // @Values{Copter, Rover, Plane, Blimp}: 177:Mount LRF enable + // @Values{Copter}: 178:FlightMode Pause/Resume // @Values{Rover}: 201:Roll // @Values{Rover}: 202:Pitch // @Values{Rover}: 207:MainSail diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 6d4af944fe..2d8d1ab850 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -250,6 +250,7 @@ public: CAMERA_LENS = 175, // camera lens selection VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method 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