AP_Camera: allow features override. Report OSD support.
This commit is contained in:
parent
318a23537d
commit
d8a58ebda4
@ -886,9 +886,15 @@ void AP_RunCam::parse_device_info(const Request& request)
|
||||
|
||||
uint8_t featureLowBits = request._recv_buf[2];
|
||||
uint8_t featureHighBits = request._recv_buf[3];
|
||||
_features = (featureHighBits << 8) | featureLowBits;
|
||||
if (!has_feature(Feature::FEATURES_OVERRIDE)) {
|
||||
_features = (featureHighBits << 8) | featureLowBits;
|
||||
}
|
||||
_state = State::INITIALIZED;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "RunCam device initialized, features 0x%04X\n", _features.get());
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "RunCam initialized, features 0x%04X, %d-key OSD\n", _features.get(),
|
||||
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE) ? 5 :
|
||||
(has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE) &&
|
||||
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON) &&
|
||||
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON)) ? 2 : 0);
|
||||
debug("RunCam: initialized state: video: %d, osd: %d, cam: %d\n", _video_recording, int(_osd_option), int(_cam_control_option));
|
||||
}
|
||||
|
||||
|
@ -105,7 +105,8 @@ private:
|
||||
RCDEVICE_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS = (1 << 4),
|
||||
RCDEVICE_PROTOCOL_FEATURE_DISPLAY_PORT = (1 << 5),
|
||||
RCDEVICE_PROTOCOL_FEATURE_START_RECORDING = (1 << 6),
|
||||
RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING = (1 << 7)
|
||||
RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING = (1 << 7),
|
||||
FEATURES_OVERRIDE = (1 << 14)
|
||||
};
|
||||
|
||||
// camera control commands
|
||||
@ -190,10 +191,6 @@ private:
|
||||
|
||||
// supported features, usually probed from the device
|
||||
AP_Int16 _features;
|
||||
// number of initialization attempts
|
||||
AP_Int8 _init_attempts;
|
||||
// delay between initialization attempts
|
||||
AP_Int32 _init_attempt_interval_ms;
|
||||
// delay time to make sure the camera is fully booted
|
||||
AP_Int32 _boot_delay_ms;
|
||||
// delay time to make sure a button press has been activated
|
||||
|
Loading…
Reference in New Issue
Block a user