mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_Mount: In Siyi, clean up toggling of video recording
This commit is contained in:
parent
a8e10ca59b
commit
bad73df582
@ -708,18 +708,45 @@ bool AP_Mount_Siyi::record_video(bool start_recording)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// check desired recording state has changed
|
bool success = true;
|
||||||
bool ret = true;
|
bool send_toggle = false;
|
||||||
const RecordingStatus new_record_status = start_recording ? RecordingStatus::ON : RecordingStatus::OFF;
|
if (start_recording) {
|
||||||
if (_config_info.record_status != new_record_status) {
|
switch (_config_info.record_status) {
|
||||||
// request recording start or stop (sadly the same message is used)
|
case RecordingStatus::ON:
|
||||||
ret = send_1byte_packet(SiyiCommandId::PHOTO, (uint8_t)PhotoFunction::RECORD_VIDEO_TOGGLE);
|
// already recording...
|
||||||
|
break;
|
||||||
|
// assume that DATA_LOSS is the same as OFF
|
||||||
|
case RecordingStatus::DATA_LOSS:
|
||||||
|
case RecordingStatus::OFF:
|
||||||
|
send_toggle = true;
|
||||||
|
break;
|
||||||
|
case RecordingStatus::NO_CARD:
|
||||||
|
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Siyi: can't start recording: No Card");
|
||||||
|
success = false;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
switch (_config_info.record_status) {
|
||||||
|
case RecordingStatus::ON:
|
||||||
|
send_toggle = true;
|
||||||
|
break;
|
||||||
|
// assume that DATA_LOSS is the same as OFF
|
||||||
|
case RecordingStatus::DATA_LOSS:
|
||||||
|
case RecordingStatus::OFF:
|
||||||
|
case RecordingStatus::NO_CARD:
|
||||||
|
// already off...
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (send_toggle) {
|
||||||
|
success = send_1byte_packet(SiyiCommandId::PHOTO, (uint8_t)PhotoFunction::RECORD_VIDEO_TOGGLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
// request recording state update from gimbal
|
// request recording state update from gimbal
|
||||||
request_configuration();
|
request_configuration();
|
||||||
|
|
||||||
return ret;
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
// send zoom rate command to camera. zoom out = -1, hold = 0, zoom in = 1
|
// send zoom rate command to camera. zoom out = -1, hold = 0, zoom in = 1
|
||||||
|
Loading…
Reference in New Issue
Block a user