Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Mount: added support for sending gimbal rates to GCS #25551

Merged
merged 2 commits into from
Nov 16, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 5 additions & 3 deletions libraries/AP_Mount/AP_Mount_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,8 @@ void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan
if (!get_attitude_quaternion(att_quat)) {
return;
}
Vector3f ang_velocity { nanf(""), nanf(""), nanf("") };
IGNORE_RETURN(get_angular_velocity(ang_velocity));

// construct quaternion array
const float quat_array[4] = {att_quat.q1, att_quat.q2, att_quat.q3, att_quat.q4};
Expand All @@ -152,9 +154,9 @@ void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan
AP_HAL::millis(), // autopilot system time
get_gimbal_device_flags(),
quat_array, // attitude expressed as quaternion
std::numeric_limits<double>::quiet_NaN(), // roll axis angular velocity (NaN for unknown)
std::numeric_limits<double>::quiet_NaN(), // pitch axis angular velocity (NaN for unknown)
std::numeric_limits<double>::quiet_NaN(), // yaw axis angular velocity (NaN for unknown)
ang_velocity.x, // roll axis angular velocity (NaN for unknown)
ang_velocity.y, // pitch axis angular velocity (NaN for unknown)
ang_velocity.z, // yaw axis angular velocity (NaN for unknown)
0, // failure flags (not supported)
std::numeric_limits<double>::quiet_NaN(), // delta_yaw (NaN for unknonw)
std::numeric_limits<double>::quiet_NaN(), // delta_yaw_velocity (NaN for unknonw)
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Mount/AP_Mount_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ class AP_Mount_Backend
// yaw is in body-frame.
virtual bool get_attitude_quaternion(Quaternion& att_quat) = 0;

// get angular velocity of mount. Only available on some backends
virtual bool get_angular_velocity(Vector3f& rates) { return false; }

// get mount's mode
enum MAV_MOUNT_MODE get_mode() const { return _mode; }

Expand Down
20 changes: 16 additions & 4 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 @@ -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
Expand All @@ -87,7 +99,7 @@ void AP_Mount_Siyi::update()
_last_attitude_send_ms = now_ms;
send_attitude();
}

// run zoom control
update_zoom_control();

Expand Down Expand Up @@ -528,9 +540,9 @@ void AP_Mount_Siyi::process_packet()
_current_angle_rad.z = -radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+1], _msg_buff[_msg_buff_data_start]) * 0.1); // yaw angle
_current_angle_rad.y = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+3], _msg_buff[_msg_buff_data_start+2]) * 0.1); // pitch angle
_current_angle_rad.x = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+5], _msg_buff[_msg_buff_data_start+4]) * 0.1); // roll angle
//const float yaw_rate_degs = -(int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+7], _msg_buff[_msg_buff_data_start+6]) * 0.1; // yaw rate
//const float pitch_rate_deg = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+9], _msg_buff[_msg_buff_data_start+8]) * 0.1; // pitch rate
//const float roll_rate_deg = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+11], _msg_buff[_msg_buff_data_start+10]) * 0.1; // roll rate
_current_rates_rads.z = -radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+7], _msg_buff[_msg_buff_data_start+6]) * 0.1); // yaw rate
_current_rates_rads.y = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+9], _msg_buff[_msg_buff_data_start+8]) * 0.1); // pitch rate
_current_rates_rads.x = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+11], _msg_buff[_msg_buff_data_start+10]) * 0.1); // roll rate
break;
}

Expand Down
11 changes: 11 additions & 0 deletions libraries/AP_Mount/AP_Mount_Siyi.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,12 @@ class AP_Mount_Siyi : public AP_Mount_Backend
// get attitude as a quaternion. returns true on success
bool get_attitude_quaternion(Quaternion& att_quat) override;

// get angular velocity of mount. Only available on some backends
bool get_angular_velocity(Vector3f& rates) override {
rates = _current_rates_rads;
return true;
}

private:

// serial protocol command ids
Expand All @@ -112,6 +118,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 @@ -308,6 +315,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend

// actual attitude received from gimbal
Vector3f _current_angle_rad; // current angles in radians received from gimbal (x=roll, y=pitch, z=yaw)
Vector3f _current_rates_rads; // current angular rates in rad/s (x=roll, y=pitch, z=yaw)
uint32_t _last_current_angle_rad_ms; // system time _current_angle_rad was updated
uint32_t _last_req_current_angle_rad_ms; // system time that this driver last requested current angle

Expand Down Expand Up @@ -335,6 +343,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