mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_Camera: fix parameter caching with RunCam enablement and setup on 3-pos switch
This commit is contained in:
parent
e7ba5d6406
commit
e11f417231
@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
|
|||||||
// @Param: TYPE
|
// @Param: TYPE
|
||||||
// @DisplayName: RunCam device type
|
// @DisplayName: RunCam device type
|
||||||
// @Description: RunCam deviee type used to determine OSD menu structure and shutter options.
|
// @Description: RunCam deviee type used to determine OSD menu structure and shutter options.
|
||||||
// @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid
|
// @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid/RunCam Thumb Pro
|
||||||
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE),
|
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE),
|
||||||
|
|
||||||
// @Param: FEATURES
|
// @Param: FEATURES
|
||||||
@ -142,6 +142,7 @@ void AP_RunCam::init()
|
|||||||
without a runcam
|
without a runcam
|
||||||
*/
|
*/
|
||||||
_cam_type.set_default(int8_t(DeviceType::SplitMicro));
|
_cam_type.set_default(int8_t(DeviceType::SplitMicro));
|
||||||
|
AP_Param::invalidate_count();
|
||||||
}
|
}
|
||||||
if (_cam_type.get() == int8_t(DeviceType::Disabled)) {
|
if (_cam_type.get() == int8_t(DeviceType::Disabled)) {
|
||||||
uart = nullptr;
|
uart = nullptr;
|
||||||
@ -498,15 +499,17 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
|
|||||||
} else if (_osd_option == OSDOption::ENTER
|
} else if (_osd_option == OSDOption::ENTER
|
||||||
&& _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {
|
&& _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {
|
||||||
result = Event::ENTER_MENU;
|
result = Event::ENTER_MENU;
|
||||||
} else if (_osd_option == OSDOption::OPTION
|
} else if ((_osd_option == OSDOption::OPTION || _osd_option == OSDOption::ENTER)
|
||||||
&& _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) {
|
&& _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) {
|
||||||
result = Event::ENTER_MENU;
|
result = Event::ENTER_MENU;
|
||||||
} else if (_osd_option == OSDOption::EXIT
|
} else if (_osd_option == OSDOption::EXIT
|
||||||
&& _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {
|
&& _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {
|
||||||
result = Event::EXIT_MENU;
|
result = Event::EXIT_MENU;
|
||||||
} else if (_osd_option == OSDOption::NO_OPTION
|
} else if ((_osd_option == OSDOption::NO_OPTION || _osd_option == OSDOption::EXIT)
|
||||||
&& _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) {
|
&& _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) {
|
||||||
result = Event::EXIT_MENU;
|
result = Event::EXIT_MENU;
|
||||||
|
} else {
|
||||||
|
debug("map_rc_input_to_event(): nothing selected\n");
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user