AP_Camera: move get_channel_pos function to RC_Channels

This commit is contained in:
Tatsuya Yamaguchi 2020-05-02 23:12:48 +09:00 committed by Randy Mackay
parent 806bd38c7f
commit f23e592057
2 changed files with 4 additions and 18 deletions

View File

@ -265,18 +265,6 @@ void AP_RunCam::update_osd()
update_state_machine_disarmed();
}
// return radio values as LOW, MIDDLE, HIGH
RC_Channel::aux_switch_pos_t AP_RunCam::get_channel_pos(uint8_t rcmapchan) const
{
RC_Channel::aux_switch_pos_t position = RC_Channel::LOW;
const RC_Channel* chan = rc().channel(rcmapchan-1);
if (chan == nullptr || !chan->read_3pos_switch(position)) {
return RC_Channel::LOW;
}
return position;
}
// update the state machine when armed or flying
void AP_RunCam::update_state_machine_armed()
{
@ -449,10 +437,10 @@ void AP_RunCam::handle_in_menu(Event ev)
// map rc input to an event
AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
{
const RC_Channel::aux_switch_pos_t throttle = get_channel_pos(AP::rcmap()->throttle());
const RC_Channel::aux_switch_pos_t yaw = get_channel_pos(AP::rcmap()->yaw());
const RC_Channel::aux_switch_pos_t roll = get_channel_pos(AP::rcmap()->roll());
const RC_Channel::aux_switch_pos_t pitch = get_channel_pos(AP::rcmap()->pitch());
const RC_Channel::aux_switch_pos_t throttle = rc().get_channel_pos(AP::rcmap()->throttle());
const RC_Channel::aux_switch_pos_t yaw = rc().get_channel_pos(AP::rcmap()->yaw());
const RC_Channel::aux_switch_pos_t roll = rc().get_channel_pos(AP::rcmap()->roll());
const RC_Channel::aux_switch_pos_t pitch = rc().get_channel_pos(AP::rcmap()->pitch());
Event result = Event::NONE;

View File

@ -351,8 +351,6 @@ private:
// OSD update loop
void update_osd();
// return radio values as LOW, MIDDLE, HIGH
RC_Channel::aux_switch_pos_t get_channel_pos(uint8_t rcmapchan) const;
// update the state machine when armed or flying
void update_state_machine_armed();
// update the state machine when disarmed