|
|
|
@ -165,6 +165,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
@@ -165,6 +165,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
|
|
|
|
|
componentMulti[i] = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
connect(this, &UAS::_sendMessageOnThread, this, &UAS::_sendMessage, Qt::QueuedConnection); |
|
|
|
|
connect(this, &UAS::_sendMessageOnThreadLink, this, &UAS::_sendMessageLink, Qt::QueuedConnection); |
|
|
|
|
connect(mavlink, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), &fileManager, SLOT(receiveMessage(LinkInterface*,mavlink_message_t))); |
|
|
|
|
|
|
|
|
|
// Store a list of available actions for this UAS.
|
|
|
|
@ -1729,6 +1731,15 @@ void UAS::setModeArm(uint8_t newBaseMode, uint32_t newCustomMode)
@@ -1729,6 +1731,15 @@ void UAS::setModeArm(uint8_t newBaseMode, uint32_t newCustomMode)
|
|
|
|
|
*/ |
|
|
|
|
void UAS::sendMessage(mavlink_message_t message) |
|
|
|
|
{ |
|
|
|
|
emit _sendMessageOnThread(message); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Send a message to every link that is connected. |
|
|
|
|
* @param message that is to be sent |
|
|
|
|
*/ |
|
|
|
|
void UAS::_sendMessage(mavlink_message_t message) |
|
|
|
|
{ |
|
|
|
|
if (!LinkManager::instance()) |
|
|
|
|
{ |
|
|
|
|
qDebug() << "LINKMANAGER NOT AVAILABLE!"; |
|
|
|
@ -1757,6 +1768,16 @@ void UAS::sendMessage(mavlink_message_t message)
@@ -1757,6 +1768,16 @@ void UAS::sendMessage(mavlink_message_t message)
|
|
|
|
|
*/ |
|
|
|
|
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message) |
|
|
|
|
{ |
|
|
|
|
emit _sendMessageOnThreadLink(link, message); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Send a message to the link that is connected. |
|
|
|
|
* @param link that the message will be sent to |
|
|
|
|
* @message that is to be sent |
|
|
|
|
*/ |
|
|
|
|
void UAS::_sendMessageLink(LinkInterface* link, mavlink_message_t message) |
|
|
|
|
{ |
|
|
|
|
if(!link) return; |
|
|
|
|
// Create buffer
|
|
|
|
|
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; |
|
|
|
|