AP_Mount: set clock on SIYI

this means photos on microSD have correct date
This commit is contained in:
Andrew Tridgell 2023-11-15 13:24:28 +11:00
parent c09352102e
commit 7472f76336
2 changed files with 16 additions and 0 deletions

View File

@ -6,6 +6,7 @@
#include <GCS_MAVLink/GCS.h>
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_RTC/AP_RTC.h>
extern const AP_HAL::HAL& hal;
@ -68,6 +69,17 @@ void AP_Mount_Siyi::update()
} else {
request_configuration();
}
#if AP_RTC_ENABLED
// send UTC time to the camera
if (sent_time_count < 5) {
uint64_t utc_usec;
if (AP::rtc().get_utc_usec(utc_usec) &&
send_packet(SiyiCommandId::SET_TIME, (const uint8_t *)&utc_usec, sizeof(utc_usec))) {
sent_time_count++;
}
}
#endif
}
// request attitude at regular intervals

View File

@ -112,6 +112,7 @@ private:
SET_CAMERA_IMAGE_TYPE = 0x11,
READ_RANGEFINDER = 0x15,
EXTERNAL_ATTITUDE = 0x22,
SET_TIME = 0x30,
};
// Function Feedback Info packet info_type values
@ -335,6 +336,9 @@ private:
const char* model_name;
};
static const HWInfo hardware_lookup_table[];
// count of SET_TIME packets, we send 5 times to cope with packet loss
uint8_t sent_time_count;
};
#endif // HAL_MOUNT_SIYISERIAL_ENABLED