diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index ba47d2db17a1e999f880d929031314f89c193137..9e39e10a79facff23b3dbee0226c199d464e5600 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -40,9 +40,10 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(const QString& title, QAction* action, connect(ui->clearButton, &QPushButton::clicked, this, &QGCMAVLinkInspector::clearView); - // Connect external connections - connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &QGCMAVLinkInspector::_vehicleAdded); - connect(protocol, &MAVLinkProtocol::messageReceived, this, &QGCMAVLinkInspector::receiveMessage); + MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager(); + connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &QGCMAVLinkInspector::_vehicleAdded); + connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &QGCMAVLinkInspector::_vehicleRemoved); + connect(protocol, &MAVLinkProtocol::messageReceived, this, &QGCMAVLinkInspector::receiveMessage); // Attach the UI's refresh rate to a timer. connect(&updateTimer, &QTimer::timeout, this, &QGCMAVLinkInspector::refreshView); @@ -56,7 +57,12 @@ void QGCMAVLinkInspector::_vehicleAdded(Vehicle* vehicle) ui->systemComboBox->addItem(tr("Vehicle %1").arg(vehicle->id()), vehicle->id()); // Add a tree for a new UAS - addUAStoTree(vehicle->id()); + addVehicleToTree(vehicle->id()); +} + +void QGCMAVLinkInspector::_vehicleRemoved(Vehicle* vehicle) +{ + removeVehicleFromTree(vehicle->id()); } void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid) @@ -165,8 +171,6 @@ void QGCMAVLinkInspector::clearView() } uasLastMessageUpdate.clear(); - onboardMessageInterval.clear(); - ui->treeWidget->clear(); } @@ -230,7 +234,7 @@ void QGCMAVLinkInspector::refreshView() QString messageName("%1 (%2 Hz, #%3)"); messageName = messageName.arg(msgInfo->name).arg(msgHz, 3, 'f', 1).arg(msg->msgid); - addUAStoTree(msg->sysid); + addVehicleToTree(msg->sysid); // Look for the tree for the UAS sysid QMap* msgTreeItems = uasMsgTreeItems.value(msg->sysid); @@ -271,26 +275,28 @@ void QGCMAVLinkInspector::refreshView() } } -void QGCMAVLinkInspector::addUAStoTree(int sysId) +void QGCMAVLinkInspector::addVehicleToTree(int vehicleId) { - if(!uasTreeWidgetItems.contains(sysId)) - { - // Add the UAS to the main tree after it has been created - Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->getVehicleById(sysId); - if (vehicle) - { - UASInterface* uas = vehicle->uas(); - QStringList idstring; - idstring << QString("Vehicle %1").arg(uas->getUASID()); - QTreeWidgetItem* uasWidget = new QTreeWidgetItem(idstring); - uasWidget->setFirstColumnSpanned(true); - uasTreeWidgetItems.insert(sysId,uasWidget); - ui->treeWidget->addTopLevelItem(uasWidget); - uasMsgTreeItems.insert(sysId,new QMap()); - } + if (!uasTreeWidgetItems.contains(vehicleId)) { + QStringList idstring; + idstring << tr("Vehicle %1").arg(vehicleId); + QTreeWidgetItem* uasWidget = new QTreeWidgetItem(idstring); + uasWidget->setFirstColumnSpanned(true); + uasTreeWidgetItems.insert(vehicleId, uasWidget); + ui->treeWidget->addTopLevelItem(uasWidget); + uasMsgTreeItems.insert(vehicleId, new QMap()); } } +void QGCMAVLinkInspector::removeVehicleFromTree(int vehicleId) +{ + Q_UNUSED(vehicleId); + + // This doesn't work with multi-vehicle. But this code is so screwed up and crufty it's not worth the effort making that work. + // Especially since mult-vehicle support here has been broken for ages. Better to at least get single vehicle working. + clearView(); +} + void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t message) { Q_UNUSED(link); @@ -396,22 +402,6 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m lastMsgUpdate->insert(message.msgid,receiveTime); } - if (selectedSystemID == 0 || selectedComponentID == 0) - { - return; - } - - switch (message.msgid) - { - case MAVLINK_MSG_ID_DATA_STREAM: - { - mavlink_data_stream_t stream; - mavlink_msg_data_stream_decode(&message, &stream); - onboardMessageInterval.insert(stream.stream_id, stream.message_rate); - } - break; - - } } QGCMAVLinkInspector::~QGCMAVLinkInspector() diff --git a/src/ui/QGCMAVLinkInspector.h b/src/ui/QGCMAVLinkInspector.h index 3953beab033a8fe083c64d9536e5dacdcfc045d9..888ea1ce2d43a96c44dceb31ec1c85b61d9de262 100644 --- a/src/ui/QGCMAVLinkInspector.h +++ b/src/ui/QGCMAVLinkInspector.h @@ -39,9 +39,7 @@ protected: MAVLinkProtocol *_protocol; ///< MAVLink instance int selectedSystemID; ///< Currently selected system int selectedComponentID; ///< Currently selected component - QMap systems; ///< Already observed systems QMap components; ///< Already observed components - QMap onboardMessageInterval; ///< Stores the onboard selected data rate QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI QMap uasTreeWidgetItems; ///< Tree of available uas with their widget @@ -54,18 +52,17 @@ protected: QMap* > uasLastMessageUpdate; ///< Stores the time of the last message for each message of each UAS - /* @brief Update one message field */ void updateField(mavlink_message_t* msg, const mavlink_message_info_t* msgInfo, int fieldid, QTreeWidgetItem* item); - /** @brief Rebuild the list of components */ void rebuildComponentList(); - /* @brief Create a new tree for a new UAS */ - void addUAStoTree(int sysId); + void addVehicleToTree(int vehicleId); + void removeVehicleFromTree(int vehicleId); static const unsigned int updateInterval; ///< The update interval of the refresh function static const float updateHzLowpass; ///< The low-pass filter value for the frequency of each message private slots: - void _vehicleAdded(Vehicle* vehicle); + void _vehicleAdded (Vehicle* vehicle); + void _vehicleRemoved(Vehicle* vehicle); private: Ui::QGCMAVLinkInspector *ui;