Commit d4616625 authored by oberion's avatar oberion

Intermediate step

parent 79d78668
...@@ -340,7 +340,7 @@ QVector<QString>* SerialLink::getCurrentPorts() ...@@ -340,7 +340,7 @@ QVector<QString>* SerialLink::getCurrentPorts()
QextPortInfo portInfo = ports.at(i); QextPortInfo portInfo = ports.at(i);
QString portString = QString(portInfo.portName.toLocal8Bit().constData()) + " - " + QString(ports.at(i).friendName.toLocal8Bit().constData()).split("(").first(); QString portString = QString(portInfo.portName.toLocal8Bit().constData()) + " - " + QString(ports.at(i).friendName.toLocal8Bit().constData()).split("(").first();
// Prepend newly found port to the list // Prepend newly found port to the list
ports.append(portString); this->ports->append(portString);
} }
//printf("port name: %s\n", ports.at(i).portName.toLocal8Bit().constData()); //printf("port name: %s\n", ports.at(i).portName.toLocal8Bit().constData());
...@@ -349,7 +349,7 @@ QVector<QString>* SerialLink::getCurrentPorts() ...@@ -349,7 +349,7 @@ QVector<QString>* SerialLink::getCurrentPorts()
//printf("enumerator name: %s\n", ports.at(i).enumName.toLocal8Bit().constData()); //printf("enumerator name: %s\n", ports.at(i).enumName.toLocal8Bit().constData());
//printf("===================================\n\n"); //printf("===================================\n\n");
#endif #endif
return ports; return this->ports;
} }
void SerialLink::loadSettings() void SerialLink::loadSettings()
......
...@@ -72,6 +72,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -72,6 +72,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav; uas = mav;
} }
break; break;
#ifdef QGC_USE_SENSESOAR_MESSAGES
case MAV_AUTOPILOT_SENSESOAR: case MAV_AUTOPILOT_SENSESOAR:
{ {
senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid); senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid);
...@@ -80,6 +81,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -80,6 +81,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav; uas = mav;
break; break;
} }
#endif
default: default:
{ {
UAS* mav = new UAS(mavlink, sysid); UAS* mav = new UAS(mavlink, sysid);
......
...@@ -248,8 +248,6 @@ UASManager::~UASManager() ...@@ -248,8 +248,6 @@ UASManager::~UASManager()
foreach (UASInterface* mav, systems) { foreach (UASInterface* mav, systems) {
delete mav; delete mav;
} }
this->quit();
this->wait();
} }
void UASManager::addUAS(UASInterface* uas) void UASManager::addUAS(UASInterface* uas)
......
...@@ -1499,7 +1499,7 @@ QList<QAction*> MainWindow::listLinkMenuActions(void) ...@@ -1499,7 +1499,7 @@ QList<QAction*> MainWindow::listLinkMenuActions(void)
{ {
return ui.menuNetwork->actions(); return ui.menuNetwork->actions();
} }
/*
void MainWindow::buildSenseSoarWidgets() void MainWindow::buildSenseSoarWidgets()
{ {
if (!linechartWidget) if (!linechartWidget)
...@@ -1603,3 +1603,4 @@ void MainWindow::arrangeSenseSoarCenterStack() ...@@ -1603,3 +1603,4 @@ void MainWindow::arrangeSenseSoarCenterStack()
void MainWindow::connectSenseSoarActions() void MainWindow::connectSenseSoarActions()
{ {
} }
*/
\ No newline at end of file
...@@ -13,8 +13,8 @@ ...@@ -13,8 +13,8 @@
<message id="170" name="OBS_POSITION"> <message id="170" name="OBS_POSITION">
Position estimate of the observer in global frame Position estimate of the observer in global frame
<field type="int32_t" name="lon">Longitude expressed in 1E7</field> <field type="int32_t" name="lon">Longitude expressed in 1E7</field>
<field type="int32_t" name="lat">Latitude expressed in 1E7</field> <field type="int32_t" name="lat">Latitude expressed in 1E7</field>
<field type="int32_t" name="alt">Altitude expressed in milimeters</field> <field type="int32_t" name="alt">Altitude expressed in milimeters</field>
</message> </message>
<message id="172" name="OBS_VELOCITY"> <message id="172" name="OBS_VELOCITY">
velocity estimate of the observer in NED inertial frame velocity estimate of the observer in NED inertial frame
......
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