Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add RC option for flightmode pause/resume #26748

Merged
merged 2 commits into from
Apr 11, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 16 additions & 0 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::SIMPLE_HEADING_RESET:
case AUX_FUNC::ARMDISARM_AIRMODE:
case AUX_FUNC::TURBINE_START:
case AUX_FUNC::FLIGHTMODE_PAUSE:
break;
case AUX_FUNC::ACRO_TRAINER:
case AUX_FUNC::ATTCON_ACCEL_LIM:
Expand Down Expand Up @@ -566,6 +567,21 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
}
break;

case AUX_FUNC::FLIGHTMODE_PAUSE:
switch (ch_flag) {
case AuxSwitchPos::HIGH:
if (!copter.flightmode->pause()) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Flight Mode Pause failed");
}
break;
case AuxSwitchPos::MIDDLE:
break;
case AuxSwitchPos::LOW:
copter.flightmode->resume();
break;
}
break;

case AUX_FUNC::ZIGZAG_Auto:
#if MODE_ZIGZAG_ENABLED == ENABLED
if (copter.flightmode == &copter.mode_zigzag) {
Expand Down
1 change: 1 addition & 0 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 1 addition & 0 deletions libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -250,6 +250,7 @@ class RC_Channel {
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
Expand Down
Loading