Commit 710ca1a9 authored by Mariano Lizarraga's avatar Mariano Lizarraga

Merge branch 'experimental' of git://github.com/amolinap/qgroundcontrol into mergeRemote

Conflicts:
	qgcunittest/UASUnitTest.cc
	qgcunittest/UASUnitTest.h
	qgroundcontrol.pro
	src/uas/SlugsMAV.cc
	src/uas/UAS.cc
	src/uas/UAS.h
	src/uas/UASManager.cc
	src/ui/MainWindow.cc
	src/ui/MapWidget.cc
	src/ui/QGCRemoteControlView.cc
	src/ui/WaypointList.cc
	src/ui/uas/UASView.cc
parents afaea4b3 acc50f49
......@@ -368,11 +368,13 @@ namespace qmapcontrol
layermanager->zoomIn();
update();
}
void MapControl::zoomOut()
{
layermanager->zoomOut();
update();
}
void MapControl::setZoom(int zoomlevel)
{
layermanager->setZoom(zoomlevel);
......
#include "SlugsMavUnitTest.h"
SlugsMavUnitTest::SlugsMavUnitTest()
{
}
void SlugsMavUnitTest::initTestCase()
{
}
void SlugsMavUnitTest::cleanupTestCase()
{
}
void SlugsMavUnitTest::first_test()
{
QCOMPARE(1,2);
}
#include "SlugsMavUnitTest.h"
SlugsMavUnitTest::SlugsMavUnitTest()
{
}
void SlugsMavUnitTest::initTestCase()
{
mav = new MAVLinkProtocol();
slugsMav = new SlugsMAV(mav, UASID);
}
void SlugsMavUnitTest::cleanupTestCase()
{
delete slugsMav;
delete mav;
}
void SlugsMavUnitTest::first_test()
{
QCOMPARE(1,1);
}
void SlugsMavUnitTest::getPwmCommands_test()
{
mavlink_pwm_commands_t* k = slugsMav->getPwmCommands();
k->aux1=80;
mavlink_pwm_commands_t* k2 = slugsMav->getPwmCommands();
k2->aux1=81;
QCOMPARE(k->aux1, k2->aux1);
}
#ifndef SLUGSMAVUNITTEST_H
#define SLUGSMAVUNITTEST_H
#include <QObject>
#include <QtCore/QString>
#include <QtTest/QtTest>
#include "UAS.h"
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "AutoTest.h"
class SlugsMavUnitTest : public QObject
{
Q_OBJECT
public:
SlugsMavUnitTest();
signals:
private slots:
void initTestCase();
void cleanupTestCase();
void first_test();
};
DECLARE_TEST(SlugsMavUnitTest)
#endif // SLUGSMAVUNITTEST_H
#ifndef SLUGSMAVUNITTEST_H
#define SLUGSMAVUNITTEST_H
#include <QObject>
#include <QtCore/QString>
#include <QtTest/QtTest>
#include "UAS.h"
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "AutoTest.h"
#include "SlugsMAV.h"
class SlugsMavUnitTest : public QObject
{
Q_OBJECT
public:
#define UASID 5
MAVLinkProtocol* mav;
SlugsMAV* slugsMav;
SlugsMavUnitTest();
signals:
private slots:
void initTestCase();
void cleanupTestCase();
void first_test();
void getPwmCommands_test();
};
DECLARE_TEST(SlugsMavUnitTest)
#endif // SLUGSMAVUNITTEST_H
This diff is collapsed.
......@@ -4,51 +4,63 @@
#include <QObject>
#include <QtCore/QString>
#include <QtTest/QtTest>
#include <QApplication>
#include "UAS.h"
#include "MAVLinkProtocol.h"
#include "SerialLink.h"
#include "UASInterface.h"
#include "AutoTest.h"
#include "LinkManager.h"
#include "UASWaypointManager.h"
#include "SerialLink.h"
#include "LinkInterface.h"
class UASUnitTest : public QObject
{
Q_OBJECT
public:
#define UASID 50
MAVLinkProtocol* mav;
UAS* uas;
SerialLink* link;
UASUnitTest();
#define UASID 100
MAVLinkProtocol* mav;
UAS* uas;
UASUnitTest();
signals:
private slots:
void initTestCase();
void cleanupTestCase();
void getUASID_test();
void getUASName_test();
void getUpTime_test();
void getCommunicationStatus_test();
void filterVoltage_test();
void getAutopilotType_test();
void setAutopilotType_test();
void getStatusForCode_test();
void getLocalX_test();
void getLocalY_test();
void getLocalZ_test();
void getLatitude_test();
void getLongitude_test();
void getAltitude_test();
void getRoll_test();
void getPitch_test();
void getYaw_test();
void attitudeLimitsZero_test();
void attitudeLimitsPi_test();
void attitudeLimitsMinusPi_test();
void attitudeLimitsTwoPi_test();
void attitudeLimitsMinusTwoPi_test();
void attitudeLimitsTwoPiOne_test();
void attitudeLimitsMinusTwoPiOne_test();
void initTestCase();
void cleanupTestCase();
void getUASID_test();
void getUASName_test();
void getUpTime_test();
void getCommunicationStatus_test();
void filterVoltage_test();
void getAutopilotType_test();
void setAutopilotType_test();
void getStatusForCode_test();
void getLocalX_test();
void getLocalY_test();
void getLocalZ_test();
void getLatitude_test();
void getLongitude_test();
void getAltitude_test();
void getRoll_test();
void getPitch_test();
void getYaw_test();
void getSelected_test();
void getSystemType_test();
void getAirframe_test();
void getWaypointList_test();
void getWaypoint_test();
void signalWayPoint_test();
void signalUASLink_test();
void signalIdUASLink_test();
protected:
UAS *prueba;
......
......@@ -458,3 +458,6 @@ win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin)
FORMS += src/ui/OpalLinkSettings.ui
DEFINES += OPAL_RT
}
TRANSLATIONS += es-MX.ts \
en-US.ts
......@@ -7,7 +7,8 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
// Place other initializers here
{
widgetTimer = new QTimer (this);
widgetTimer->setInterval(SLUGS_UPDATE_RATE);
widgetTimer->setInterval(200);//SLUGS_UPDATE_RATE);
qDebug() << "SLUGS_UPDATE_RATE: " << SLUGS_UPDATE_RATE;
connect (widgetTimer, SIGNAL(timeout()),
this, SLOT(emitSignals()));
......@@ -72,6 +73,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_RAW_IMU:
//mavlink_raw_imu_t t;
mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
break;
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef SLUGSMAV_H
#define SLUGSMAV_H
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
#define SLUGS_UPDATE_RATE 100 // in ms
class SlugsMAV : public UAS
{
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
void emitSignals (void);
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pwm_commands_t* getPwmCommands();
#endif
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
void slugsGPSCogSog(int uasId, double cog, double sog);
#ifdef MAVLINK_ENABLED_SLUGS
void slugsCPULoad(int systemId, const mavlink_cpu_load_t& cpuLoad);
void slugsAirData(int systemId, const mavlink_air_data_t& airData);
void slugsSensorBias(int systemId, const mavlink_sensor_bias_t& sensorBias);
void slugsDiagnostic(int systemId, const mavlink_diagnostic_t& diagnostic);
void slugsPilotConsolePWM(int systemId, const mavlink_pilot_console_t& pilotConsole);
void slugsPWM(int systemId, const mavlink_pwm_commands_t& pwmCommands);
void slugsNavegation(int systemId, const mavlink_slugs_navigation_t& slugsNavigation);
void slugsDataLog(int systemId, const mavlink_data_log_t& dataLog);
void slugsFilteredData(int systemId, const mavlink_filtered_data_t& filteredData);
void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);
void slugsPidValues(int systemId, const mavlink_pid_t& pidValues);
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif
protected:
typedef struct _mavlink_pid_values_t {
float P[11];
float I[11];
float D[11];
}mavlink_pid_values_t;
unsigned char updateRoundRobin;
QTimer* widgetTimer;
mavlink_raw_imu_t mlRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_raw_t mlGpsData;
mavlink_attitude_t mlAttitude;
mavlink_cpu_load_t mlCpuLoadData;
mavlink_air_data_t mlAirData;
mavlink_sensor_bias_t mlSensorBiasData;
mavlink_diagnostic_t mlDiagnosticData;
mavlink_pilot_console_t mlPilotConsoleData;
mavlink_filtered_data_t mlFilteredData;
mavlink_boot_t mlBoot;
mavlink_gps_date_time_t mlGpsDateTime;
mavlink_mid_lvl_cmds_t mlMidLevelCommands;
mavlink_set_mode_t mlApMode;
mavlink_pwm_commands_t mlPwmCommands;
mavlink_pid_values_t mlPidValues;
mavlink_pid_t mlSinglePid;
mavlink_slugs_navigation_t mlNavigation;
mavlink_data_log_t mlDataLog;
mavlink_ctrl_srfc_pt_t mlPassthrough;
mavlink_action_ack_t mlActionAck;
mavlink_slugs_action_t mlAction;
// Standart messages MAVLINK used by SLUGS
private:
void emitGpsSignals (void);
void emitPidSignal(void);
int uasId;
#endif // if SLUGS
};
#endif // SLUGSMAV_H
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef SLUGSMAV_H
#define SLUGSMAV_H
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
#define SLUGS_UPDATE_RATE 100 // in ms
class SlugsMAV : public UAS
{
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
void emitSignals (void);
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pwm_commands_t* getPwmCommands();
#endif
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
void slugsGPSCogSog(int uasId, double cog, double sog);
#ifdef MAVLINK_ENABLED_SLUGS
void slugsCPULoad(int systemId, const mavlink_cpu_load_t& cpuLoad);
void slugsAirData(int systemId, const mavlink_air_data_t& airData);
void slugsSensorBias(int systemId, const mavlink_sensor_bias_t& sensorBias);
void slugsDiagnostic(int systemId, const mavlink_diagnostic_t& diagnostic);
void slugsPilotConsolePWM(int systemId, const mavlink_pilot_console_t& pilotConsole);
void slugsPWM(int systemId, const mavlink_pwm_commands_t& pwmCommands);
void slugsNavegation(int systemId, const mavlink_slugs_navigation_t& slugsNavigation);
void slugsDataLog(int systemId, const mavlink_data_log_t& dataLog);
void slugsFilteredData(int systemId, const mavlink_filtered_data_t& filteredData);
void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);
void slugsPidValues(int systemId, const mavlink_pid_t& pidValues);
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif
protected:
typedef struct _mavlink_pid_values_t {
float P[11];
float I[11];
float D[11];
}mavlink_pid_values_t;
unsigned char updateRoundRobin;
QTimer* widgetTimer;
mavlink_raw_imu_t mlRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_raw_t mlGpsData;
mavlink_attitude_t mlAttitude;
mavlink_cpu_load_t mlCpuLoadData;
mavlink_air_data_t mlAirData;
mavlink_sensor_bias_t mlSensorBiasData;
mavlink_diagnostic_t mlDiagnosticData;
mavlink_pilot_console_t mlPilotConsoleData;
mavlink_filtered_data_t mlFilteredData;
mavlink_boot_t mlBoot;
mavlink_gps_date_time_t mlGpsDateTime;
mavlink_mid_lvl_cmds_t mlMidLevelCommands;
mavlink_set_mode_t mlApMode;
mavlink_pwm_commands_t mlPwmCommands;
mavlink_pid_values_t mlPidValues;
mavlink_pid_t mlSinglePid;
mavlink_slugs_navigation_t mlNavigation;
mavlink_data_log_t mlDataLog;
mavlink_ctrl_srfc_pt_t mlPassthrough;
mavlink_action_ack_t mlActionAck;
mavlink_slugs_action_t mlAction;
// Standart messages MAVLINK used by SLUGS
private:
void emitGpsSignals (void);
void emitPidSignal(void);
int uasId;
#endif // if SLUGS
};
#endif // SLUGSMAV_H
......@@ -243,13 +243,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_sys_status_decode(&message, &state);
// FIXME
//qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
//qDebug() << "1 SYSTEM STATUS:" << state.status;
QString audiostring = "System " + getUASName();
QString stateAudio = "";
QString modeAudio = "";
bool statechanged = false;
bool modechanged = false;
bool modechanged = false;
if (state.status != this->status)
{
......@@ -258,6 +258,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
getStatusForCode((int)state.status, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status);
stateAudio = " changed status to " + uasState;
}
......@@ -311,6 +312,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
emit modeChanged(this->getUASID(), mode, "");
//qDebug() << "2 SYSTEM MODE:" << mode;
modeAudio = " is now in " + mode;
}
currentVoltage = state.vbat/1000.0f;
......@@ -337,6 +341,16 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// COMMUNICATIONS DROP RATE
emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
//add for development
emit remoteControlRSSIChanged(state.packet_drop/1000.0f);
float en = state.packet_drop/1000.0f;
emit remoteControlChannelRawChanged(0, en);//MAVLINK_MSG_ID_RC_CHANNELS_RAW
emit remoteControlChannelScaledChanged(0, en/100.0f);//MAVLINK_MSG_ID_RC_CHANNELS_SCALED
//qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
// AUDIO
......@@ -427,11 +441,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixTime(attitude.usec);
roll = QGC::limitAngleToPMPIf(attitude.roll);
pitch = QGC::limitAngleToPMPIf(attitude.pitch);
yaw = QGC::limitAngleToPMPIf(attitude.yaw);
emit valueChanged(uasId, "roll", "rad", roll, time);
emit valueChanged(uasId, "pitch", "rad", pitch, time);
emit valueChanged(uasId, "yaw", "rad", yaw, time);
......@@ -1226,12 +1238,16 @@ void UAS::setMode(int mode)
{
if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
{
this->mode = mode;
//this->mode = mode; //no call assignament, update receive message from UAS
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
sendMessage(msg);
qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
}
else
{
qDebug() << "uas Mode not assign: " << mode;
}
}
void UAS::sendMessage(mavlink_message_t message)
......
......@@ -355,6 +355,9 @@ protected slots:
// MESSAGE RECEPTION
/** @brief Receive a named value message */
void receiveMessageNamedValue(const mavlink_message_t& message);
private:
unsigned int mode; ///< The current mode of the MAV
};
......
......@@ -351,6 +351,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
{
waypoints[i]->setId(i);
}
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
return 0;
......
......@@ -592,30 +592,30 @@ void MainWindow::buildSlugsWidgets()
addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget(bool)), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
}
// if (!slugsDataWidget)
// {
// // Dialog widgets
// slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
// slugsDataWidget->setWidget( new SlugsDataSensorView(this));
// slugsDataWidget->setObjectName("SLUGS_DATA_DOCK_WIDGET");
// addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
// }
if (!slugsDataWidget)
{
// Dialog widgets
slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
slugsDataWidget->setWidget( new SlugsDataSensorView(this));
slugsDataWidget->setObjectName("SLUGS_DATA_DOCK_WIDGET");
addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget(bool)), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
}
// if (!slugsPIDControlWidget)
// {
// slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
// slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
// slugsPIDControlWidget->setObjectName("SLUGS_PID_CONTROL_DOCK_WIDGET");
// addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
// }
if (!slugsPIDControlWidget)
{
slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
slugsPIDControlWidget->setObjectName("SLUGS_PID_CONTROL_DOCK_WIDGET");
addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
}
// if (!slugsHilSimWidget)
// {
// slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
// slugsHilSimWidget->setWidget( new SlugsHilSim(this));
// slugsHilSimWidget->setObjectName("SLUGS_HIL_SIM_DOCK_WIDGET");
// addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
// }
if (!slugsHilSimWidget)
{
slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
slugsHilSimWidget->setWidget( new SlugsHilSim(this));
slugsHilSimWidget->setObjectName("SLUGS_HIL_SIM_DOCK_WIDGET");
addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
}
// if (!slugsCamControlWidget)
// {
......@@ -990,6 +990,7 @@ void MainWindow::updateLocationSettings (Qt::DockWidgetArea location)
}
}
/**
* Connect the signals and slots of the common window widgets
*/
......@@ -1004,6 +1005,12 @@ void MainWindow::connectCommonWidgets()
if (mapWidget && waypointsDockWidget->widget())
{
//
connect(waypointsDockWidget->widget(), SIGNAL(changePointList()), mapWidget, SLOT(clearWaypoints()));
}
//TODO temporaly debug
......@@ -1026,6 +1033,7 @@ void MainWindow::createCustomWidget()
QDockWidget* dock = new QDockWidget("Unnamed Tool", this);
connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater()));
dock->setWidget(tool);
QAction* showAction = new QAction("Show Unnamed Tool", this);
connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool)));
connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool)));
......@@ -1052,7 +1060,10 @@ void MainWindow::connectSlugsWidgets()
slugsDataWidget->widget(), SLOT(setActiveUAS(UASInterface*)));
}
if (slugsPIDControlWidget && slugsPIDControlWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
slugsPIDControlWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
}
void MainWindow::arrangeCommonCenterStack()
......@@ -1682,18 +1693,27 @@ void MainWindow::UASCreated(UASInterface* uas)
// Connect Slugs Actions
connectSlugsActions();
// if(slugsDataWidget)
// {
// SlugsDataSensorView *mm = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
// if(mm)
// {
// mm->addUAS(uas);
// }
// }
// FIXME: This type checking might be redundant
// if (slugsDataWidget) {
// SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
// if (dataWidget) {
// SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
// if (mav2) {
(dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget()))->addUAS(uas);
// //loadSlugsView();
// loadGlobalOperatorView();
// }
// }
// }