Commit 78bdc052 authored by Lorenz Meier's avatar Lorenz Meier

UAS: Connect message sending via buffered signals

parent 8113009a
...@@ -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; 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))); connect(mavlink, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), &fileManager, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
// Store a list of available actions for this UAS. // Store a list of available actions for this UAS.
...@@ -1728,6 +1730,15 @@ void UAS::setModeArm(uint8_t newBaseMode, uint32_t newCustomMode) ...@@ -1728,6 +1730,15 @@ void UAS::setModeArm(uint8_t newBaseMode, uint32_t newCustomMode)
* @param message that is to be sent * @param message that is to be sent
*/ */
void UAS::sendMessage(mavlink_message_t message) 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()) if (!LinkManager::instance())
{ {
...@@ -1756,6 +1767,16 @@ void UAS::sendMessage(mavlink_message_t message) ...@@ -1756,6 +1767,16 @@ void UAS::sendMessage(mavlink_message_t message)
* @message that is to be sent * @message that is to be sent
*/ */
void UAS::sendMessage(LinkInterface* link, 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; if(!link) return;
// Create buffer // Create buffer
......
...@@ -894,6 +894,8 @@ signals: ...@@ -894,6 +894,8 @@ signals:
void groundSpeedChanged(double val, QString name); void groundSpeedChanged(double val, QString name);
void airSpeedChanged(double val, QString name); void airSpeedChanged(double val, QString name);
void bearingToWaypointChanged(double val,QString name); void bearingToWaypointChanged(double val,QString name);
void _sendMessageOnThread(mavlink_message_t message);
void _sendMessageOnThreadLink(LinkInterface* link, mavlink_message_t message);
protected: protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */ /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0); quint64 getUnixTime(quint64 time=0);
...@@ -924,6 +926,10 @@ protected slots: ...@@ -924,6 +926,10 @@ protected slots:
void writeSettings(); void writeSettings();
/** @brief Read settings from disk */ /** @brief Read settings from disk */
void readSettings(); void readSettings();
/** @brief Send a message over this link (to this or to all UAS on this link) */
void _sendMessageLink(LinkInterface* link, mavlink_message_t message);
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void _sendMessage(mavlink_message_t message);
private slots: private slots:
void _linkDisconnected(LinkInterface* link); void _linkDisconnected(LinkInterface* link);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment