Skip to content

Commit

Permalink
AP_Mount: set clock on SIYI
Browse files Browse the repository at this point in the history
this means photos on microSD have correct date
  • Loading branch information
tridge committed Nov 15, 2023
1 parent 9012809 commit ce1d8e9
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 0 deletions.
10 changes: 10 additions & 0 deletions libraries/AP_Mount/AP_Mount_Siyi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down Expand Up @@ -54,6 +55,15 @@ void AP_Mount_Siyi::update()
// reading incoming packets from gimbal
read_incoming_packets();

// 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++;
}
}

// request firmware version during startup at 1hz
// during regular operation request configuration at 1hz
uint32_t now_ms = AP_HAL::millis();
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Mount/AP_Mount_Siyi.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend
SET_CAMERA_IMAGE_TYPE = 0x11,
READ_RANGEFINDER = 0x15,
EXTERNAL_ATTITUDE = 0x22,
SET_TIME = 0x30,
};

// Function Feedback Info packet info_type values
Expand Down Expand Up @@ -335,6 +336,9 @@ class AP_Mount_Siyi : public AP_Mount_Backend
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

0 comments on commit ce1d8e9

Please sign in to comment.