mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: add and use RC_Channel_config.h
This commit is contained in:
parent
3ba349fdb6
commit
9b6aedb9e6
|
@ -444,8 +444,10 @@ private:
|
||||||
void modify_parameter(uint8_t number, Event ev);
|
void modify_parameter(uint8_t number, Event ev);
|
||||||
void modify_configured_parameter(uint8_t number, Event ev);
|
void modify_configured_parameter(uint8_t number, Event ev);
|
||||||
|
|
||||||
|
#if AP_RC_CHANNEL_ENABLED
|
||||||
Event map_rc_input_to_event() const;
|
Event map_rc_input_to_event() const;
|
||||||
RC_Channel::AuxSwitchPos get_channel_pos(uint8_t rcmapchan) const;
|
RC_Channel::AuxSwitchPos get_channel_pos(uint8_t rcmapchan) const;
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t _selected_param = 1;
|
uint8_t _selected_param = 1;
|
||||||
MenuState _menu_state = MenuState::PARAM_SELECT;
|
MenuState _menu_state = MenuState::PARAM_SELECT;
|
||||||
|
|
Loading…
Reference in New Issue