Skip to content

Commit

Permalink
AP_Mount: added sending of attitude and velocity for SIYI
Browse files Browse the repository at this point in the history
will be used by SIYI for improved gimbal control
  • Loading branch information
tridge committed Sep 11, 2023
1 parent 768e240 commit 948624e
Show file tree
Hide file tree
Showing 2 changed files with 57 additions and 0 deletions.
51 changes: 51 additions & 0 deletions libraries/AP_Mount/AP_Mount_Siyi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,12 @@ void AP_Mount_Siyi::update()
_last_rangefinder_req_ms = now_ms;
}

// send attitude to gimbal at 10Hz
if (now_ms - _last_attitude_send_ms > 100) {
_last_attitude_send_ms = now_ms;
send_attitude_velocity();
}

// run zoom control
update_zoom_control();

Expand Down Expand Up @@ -959,4 +965,49 @@ bool AP_Mount_Siyi::get_rangefinder_distance(float& distance_m) const
return true;
}

/*
send ArduPilot attitude and velocity to gimbal
*/
void AP_Mount_Siyi::send_attitude_velocity(void)
{
const auto &ahrs = AP::ahrs();
struct {
uint32_t time_boot_ms;
float roll, pitch, yaw;
float rollspeed, pitchspeed, yawspeed;
} attitude;

// get attitude as euler 312
const auto &m = ahrs.get_rotation_body_to_ned();
const auto att = m.to_euler312();
const auto &gyro = ahrs.get_gyro();
const uint32_t now_ms = AP_HAL::millis();

attitude.time_boot_ms = now_ms;
attitude.roll = att.x;
attitude.pitch = att.y;
attitude.yaw = att.z;
attitude.rollspeed = gyro.x;
attitude.pitchspeed = gyro.y;
attitude.yawspeed = gyro.z;

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

// send velocity NED
struct {
uint32_t time_boot_ms;
float vn, ve, vd;
} velocity;
Vector3f vel_ned;
if (!ahrs.get_velocity_NED(vel_ned)) {
return;
}
velocity.time_boot_ms = now_ms;
velocity.vn = vel_ned.x;
velocity.ve = vel_ned.y;
velocity.vd = vel_ned.z;

send_packet(SiyiCommandId::EXTERNAL_VELOCITY, (const uint8_t *)&velocity, sizeof(velocity));
}

#endif // HAL_MOUNT_SIYI_ENABLED
6 changes: 6 additions & 0 deletions libraries/AP_Mount/AP_Mount_Siyi.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,8 @@ class AP_Mount_Siyi : public AP_Mount_Backend
ABSOLUTE_ZOOM = 0x0F,
SET_CAMERA_IMAGE_TYPE = 0x11,
READ_RANGEFINDER = 0x15,
EXTERNAL_ATTITUDE = 0x22,
EXTERNAL_VELOCITY = 0x26,
};

// Function Feedback Info packet info_type values
Expand Down Expand Up @@ -279,6 +281,10 @@ class AP_Mount_Siyi : public AP_Mount_Backend
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 and velocity to gimbal
uint32_t _last_attitude_send_ms;
void send_attitude_velocity(void);

// hardware lookup table indexed by HardwareModel enum values (see above)
struct HWInfo {
uint8_t hwid[2];
Expand Down

0 comments on commit 948624e

Please sign in to comment.