Skip to content

Commit

Permalink
Add osd switching via stick inputs in disarm state
Browse files Browse the repository at this point in the history
Sticks inputs: roll mid && pitch high && yaw low && throttle mid

Signed-off-by: 4th <[email protected]>
  • Loading branch information
prosolvo4th committed Aug 20, 2024
1 parent 1b4fb40 commit cdc4255
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 0 deletions.
27 changes: 27 additions & 0 deletions libraries/AP_OSD/AP_OSD.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Util.h>
#include <RC_Channel/RC_Channel.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <utility>
Expand Down Expand Up @@ -599,6 +600,32 @@ void AP_OSD::update_current_screen()
last_switch_ms = 0;
}
break;
case STICKS_INPUT:
if (!AP_Notify::flags.armed) {
RC_Channels *rc_channels = RC_Channels::get_singleton();
RC_Channel *roll = rc_channels->channel(AP::rcmap()->roll() - 1);
RC_Channel *pitch = rc_channels->channel(AP::rcmap()->pitch() - 1);
RC_Channel *yaw = rc_channels->channel(AP::rcmap()->yaw() - 1);
RC_Channel *throttle = rc_channels->channel(AP::rcmap()->throttle() - 1);
if (roll->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::MIDDLE &&
pitch->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH &&
yaw->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::LOW &&
throttle->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::MIDDLE) {
if (switch_debouncer) {
uint32_t now = AP_HAL::millis();
if (now - last_switch_ms > 1000) {
next_screen();
last_switch_ms = now;
}
} else {
switch_debouncer = true;
return;
}
} else {
last_switch_ms = 0;
}
}
break;
}
switch_debouncer = false;
#endif // AP_RC_CHANNEL_ENABLED
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_OSD/AP_OSD.h
Original file line number Diff line number Diff line change
Expand Up @@ -562,6 +562,7 @@ class AP_OSD
TOGGLE=0,
PWM_RANGE=1,
AUTO_SWITCH=2,
STICKS_INPUT=3,
};

AP_Int8 osd_type;
Expand Down

0 comments on commit cdc4255

Please sign in to comment.