6#include <QtCore/QDateTime>
21 , _hasRollAxis(hasRollAxis)
22 , _hasPitchAxis(hasPitchAxis)
23 , _hasYawAxis(hasYawAxis)
24 , _hasYawFollow(hasYawFollow)
25 , _hasYawLock(hasYawLock)
26 , _hasRetract(hasRetract)
27 , _hasNeutral(hasNeutral)
37 QMutexLocker locker(&_stateMutex);
38 const qint64 nowMs = QDateTime::currentMSecsSinceEpoch();
41 if (_managerStatusIntervalUs > 0) {
42 const qint64 intervalMs = _managerStatusIntervalUs / 1000;
43 if ((nowMs - _managerStatusLastSentMs) >= intervalMs) {
44 _sendGimbalManagerStatus();
45 _managerStatusLastSentMs = nowMs;
50 if (_deviceAttitudeStatusIntervalUs > 0) {
51 const qint64 intervalMs = _deviceAttitudeStatusIntervalUs / 1000;
52 if ((nowMs - _deviceAttitudeStatusLastSentMs) >= intervalMs) {
54 if (!_manualControl) {
56 const qint64 secondsSinceEpoch = nowMs / 1000;
57 _pitch = 10.0f * qSin(secondsSinceEpoch * 0.1);
58 _yaw = 15.0f * qCos(secondsSinceEpoch * 0.15);
61 _sendGimbalDeviceAttitudeStatus();
62 _deviceAttitudeStatusLastSentMs = nowMs;
69 if (msg.msgid != MAVLINK_MSG_ID_COMMAND_LONG) {
73 mavlink_command_long_t request{};
74 mavlink_msg_command_long_decode(&msg, &request);
77 switch (request.command) {
78 case MAV_CMD_SET_MESSAGE_INTERVAL:
79 if (_handleSetMessageInterval(request)) {
80 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
85 case MAV_CMD_REQUEST_MESSAGE:
86 if (_handleRequestMessage(request)) {
87 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
92 case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
93 if (_handleGimbalManagerPitchYaw(request)) {
94 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
97 _sendCommandAck(request.command, MAV_RESULT_DENIED);
100 case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE:
101 if (_handleGimbalManagerConfigure(request)) {
102 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
105 _sendCommandAck(request.command, MAV_RESULT_DENIED);
113void MockLinkGimbal::_sendCommandAck(uint16_t command, uint8_t result)
116 qCDebug(MockLinkGimbalLog) <<
"Sending command ACK -" << QString(
"%1(%2)").arg(commandName).arg(command) <<
"result:" << (result == MAV_RESULT_ACCEPTED ?
"ACCEPTED" : result == MAV_RESULT_DENIED ?
"DENIED" : QString::number(result));
119 (void) mavlink_msg_command_ack_pack_chan(
121 MAV_COMP_ID_AUTOPILOT1,
134bool MockLinkGimbal::_handleSetMessageInterval(
const mavlink_command_long_t &request)
136 const int msgId =
static_cast<int>(request.param1);
137 const int intervalUs =
static_cast<int>(request.param2);
138 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(
static_cast<uint32_t
>(msgId));
139 QString msgName = info ? info->name : QString::number(msgId);
141 qCDebug(MockLinkGimbalLog) <<
"SET_MESSAGE_INTERVAL -" << QString(
"%1(%2)").arg(msgName).arg(msgId) <<
"intervalUs:" << intervalUs;
147 int effectiveInterval = intervalUs;
148 if (intervalUs == 0) {
149 effectiveInterval = kDefaultIntervalUs;
150 }
else if (intervalUs < -1) {
157 QMutexLocker locker(&_stateMutex);
158 if (msgId == MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS) {
159 _managerStatusIntervalUs = effectiveInterval;
160 qCDebug(MockLinkGimbalLog) << msgName <<
"interval set to" << effectiveInterval <<
"us";
162 }
else if (msgId == MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS) {
163 _deviceAttitudeStatusIntervalUs = effectiveInterval;
164 qCDebug(MockLinkGimbalLog) << msgName <<
"interval set to" << effectiveInterval <<
"us";
170bool MockLinkGimbal::_handleRequestMessage(
const mavlink_command_long_t &request)
172 const int msgId =
static_cast<int>(request.param1);
173 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(
static_cast<uint32_t
>(msgId));
174 QString msgName = info ? info->name : QString::number(msgId);
176 if (msgId == MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION) {
177 qCDebug(MockLinkGimbalLog) <<
"REQUEST_MESSAGE -" << QString(
"%1(%2)").arg(msgName).arg(msgId);
178 _sendGimbalManagerInformation();
185bool MockLinkGimbal::_handleGimbalManagerPitchYaw(
const mavlink_command_long_t &request)
194 const float requestedPitch = request.param1;
195 const float requestedYaw = request.param2;
196 const uint32_t flags =
static_cast<uint32_t
>(request.param5);
198 qCDebug(MockLinkGimbalLog) <<
"DO_GIMBAL_MANAGER_PITCHYAW - pitch:" << requestedPitch <<
"yaw:" << requestedYaw <<
"flags:" << flags;
201 const bool updatePitch = !qIsNaN(requestedPitch);
202 const bool updateYaw = !qIsNaN(requestedYaw);
204 if (!updatePitch && !updateYaw) {
205 qCDebug(MockLinkGimbalLog) <<
"DO_GIMBAL_MANAGER_PITCHYAW - no valid pitch/yaw requested (both NaN)";
212 QMutexLocker locker(&_stateMutex);
214 if (updatePitch && _hasPitchAxis) {
215 _pitch = qBound(-45.0f, requestedPitch, 45.0f);
216 _manualControl =
true;
219 if (updateYaw && _hasYawAxis) {
221 if (flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK) {
223 _yaw = qBound(-180.0f, requestedYaw, 180.0f);
226 _yaw = qBound(-180.0f, requestedYaw, 180.0f);
228 _manualControl =
true;
231 qCDebug(MockLinkGimbalLog) <<
"Gimbal commanded to pitch:" << _pitch <<
"yaw:" << _yaw <<
"- switched to manual control";
235bool MockLinkGimbal::_handleGimbalManagerConfigure(
const mavlink_command_long_t &request)
243 const uint8_t sysidPrimary =
static_cast<uint8_t
>(request.param1);
244 const uint8_t compidPrimary =
static_cast<uint8_t
>(request.param2);
245 const uint8_t sysidSecondary =
static_cast<uint8_t
>(request.param3);
246 const uint8_t compidSecondary =
static_cast<uint8_t
>(request.param4);
248 if (sysidPrimary > 0) {
249 _gimbalManagerSysidPrimary = sysidPrimary;
251 if (compidPrimary > 0) {
252 _gimbalManagerCompidPrimary = compidPrimary;
254 if (sysidSecondary > 0) {
255 _gimbalManagerSysidSecondary = sysidSecondary;
257 if (compidSecondary > 0) {
258 _gimbalManagerCompidSecondary = compidSecondary;
261 qCDebug(MockLinkGimbalLog) <<
"Gimbal manager configured - Primary:" << _gimbalManagerSysidPrimary
262 <<
"/" << _gimbalManagerCompidPrimary
263 <<
"Secondary:" << _gimbalManagerSysidSecondary
264 <<
"/" << _gimbalManagerCompidSecondary;
268void MockLinkGimbal::_sendGimbalManagerStatus()
270 qCDebug(MockLinkGimbalLog) <<
"Sending GIMBAL_MANAGER_STATUS";
273 (void) mavlink_msg_gimbal_manager_status_pack_chan(
275 MAV_COMP_ID_AUTOPILOT1,
281 _gimbalManagerSysidPrimary,
282 _gimbalManagerCompidPrimary,
283 _gimbalManagerSysidSecondary,
284 _gimbalManagerCompidSecondary);
288void MockLinkGimbal::_sendGimbalDeviceAttitudeStatus()
290 qCDebug(MockLinkGimbalLog) <<
"Sending GIMBAL_DEVICE_ATTITUDE_STATUS - pitch:" << _pitch <<
"yaw:" << _yaw <<
"manual:" << _manualControl;
293 const float rollRad = qDegreesToRadians(_roll);
294 const float pitchRad = qDegreesToRadians(_pitch);
295 const float yawRad = qDegreesToRadians(_yaw);
297 const float cy = qCos(yawRad * 0.5f);
298 const float sy = qSin(yawRad * 0.5f);
299 const float cp = qCos(pitchRad * 0.5f);
300 const float sp = qSin(pitchRad * 0.5f);
301 const float cr = qCos(rollRad * 0.5f);
302 const float sr = qSin(rollRad * 0.5f);
305 q[0] = cr * cp * cy + sr * sp * sy;
306 q[1] = sr * cp * cy - cr * sp * sy;
307 q[2] = cr * sp * cy + sr * cp * sy;
308 q[3] = cr * cp * sy - sr * sp * cy;
311 (void) mavlink_msg_gimbal_device_attitude_status_pack_chan(
318 GIMBAL_DEVICE_FLAGS_NEUTRAL | GIMBAL_DEVICE_FLAGS_ROLL_LOCK | GIMBAL_DEVICE_FLAGS_PITCH_LOCK,
327void MockLinkGimbal::_sendGimbalManagerInformation()
330 uint32_t capFlags = 0;
331 if (_hasRollAxis) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS;
332 if (_hasPitchAxis) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS;
333 if (_hasYawAxis) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS;
334 if (_hasYawFollow) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW;
335 if (_hasYawLock) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK;
336 if (_hasRetract) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
337 if (_hasNeutral) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL;
339 qCDebug(MockLinkGimbalLog) <<
"Sending GIMBAL_MANAGER_INFORMATION - capFlags:" << QString::number(capFlags, 16);
342 (void) mavlink_msg_gimbal_manager_information_pack_chan(
344 MAV_COMP_ID_AUTOPILOT1,
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
uint8_t mavlinkChannel() const
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
void run1HzTasks()
Send periodic gimbal status messages (call from 1Hz tasks)
bool handleMavlinkMessage(const mavlink_message_t &msg)
void respondWithMavlinkMessage(const mavlink_message_t &msg)
Sends the specified mavlink message to QGC.