Skip to content

Commit

Permalink
AP_Mount: added sending of position data to Siyi gimbal
Browse files Browse the repository at this point in the history
this will allow for exif tags of position for photos
  • Loading branch information
tridge committed Jun 26, 2024
1 parent c70b1c8 commit 79b4805
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 5 deletions.
28 changes: 25 additions & 3 deletions libraries/AP_Mount/AP_Mount_Siyi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void AP_Mount_Siyi::update()
// send attitude to gimbal at 10Hz
if (now_ms - _last_attitude_send_ms > 100) {
_last_attitude_send_ms = now_ms;
send_attitude();
send_attitude_position();
}

// run zoom control
Expand Down Expand Up @@ -1161,9 +1161,9 @@ void AP_Mount_Siyi::check_firmware_version() const
}

/*
send ArduPilot attitude to gimbal
send ArduPilot attitude and position to gimbal
*/
void AP_Mount_Siyi::send_attitude(void)
void AP_Mount_Siyi::send_attitude_position(void)
{
const auto &ahrs = AP::ahrs();
struct {
Expand All @@ -1185,6 +1185,28 @@ void AP_Mount_Siyi::send_attitude(void)
attitude.yawspeed = gyro.z;

send_packet(SiyiCommandId::EXTERNAL_ATTITUDE, (const uint8_t *)&attitude, sizeof(attitude));

struct {
uint32_t time_boot_ms;
int32_t lat, lon;
int32_t alt_msl, alt_ellipsoid;
Vector3f velocity_ned;
} position;
Location loc;
float undulation = 0;
if (!ahrs.get_location(loc) ||
!ahrs.get_velocity_NED(position.velocity_ned)) {
return;
}
AP::gps().get_undulation(undulation);

position.time_boot_ms = now_ms;
position.lat = loc.lat;
position.lon = loc.lng;
position.alt_msl = loc.alt;
position.alt_ellipsoid = position.alt_msl - undulation*100;

send_packet(SiyiCommandId::POSITION_DATA, (const uint8_t *)&position, sizeof(position));
}

#endif // HAL_MOUNT_SIYI_ENABLED
5 changes: 3 additions & 2 deletions libraries/AP_Mount/AP_Mount_Siyi.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend_Serial
READ_RANGEFINDER = 0x15,
EXTERNAL_ATTITUDE = 0x22,
SET_TIME = 0x30,
POSITION_DATA = 0x3e,
};

// Function Feedback Info packet info_type values
Expand Down Expand Up @@ -332,9 +333,9 @@ class AP_Mount_Siyi : public AP_Mount_Backend_Serial
uint32_t _last_rangefinder_dist_ms; // system time of last successful read of rangefinder distance
float _rangefinder_dist_m; // distance received from rangefinder

// sending of attitude to gimbal
// sending of attitude and position to gimbal
uint32_t _last_attitude_send_ms;
void send_attitude(void);
void send_attitude_position(void);

// hardware lookup table indexed by HardwareModel enum values (see above)
struct HWInfo {
Expand Down

0 comments on commit 79b4805

Please sign in to comment.