From 20d72b17a86f358a30d02ce81d18c77217638355 Mon Sep 17 00:00:00 2001
From: lm <pixhawk@switched.com>
Date: Thu, 13 Jan 2011 17:59:41 +0100
Subject: [PATCH] Fixed a couple of serial link bugs only showing in windows

---
 src/comm/MAVLinkSimulationMAV.cc |   2 +-
 src/comm/SerialLink.cc           | 113 ++++++++++++---------------------------
 src/uas/SlugsMAV.h               |   2 +-
 src/ui/MainWindow.cc             |  14 ++---
 4 files changed, 42 insertions(+), 89 deletions(-)

diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc
index f2b881e..3af6539 100644
--- a/src/comm/MAVLinkSimulationMAV.cc
+++ b/src/comm/MAVLinkSimulationMAV.cc
@@ -17,7 +17,7 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
 void MAVLinkSimulationMAV::mainloop()
 {
     mavlink_message_t msg;
-    mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA);
+    mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_SLUGS);
     link->sendMAVLinkMessage(&msg);
 }
 
diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc
index 8d857dd..d6bc78c 100644
--- a/src/comm/SerialLink.cc
+++ b/src/comm/SerialLink.cc
@@ -593,15 +593,9 @@ bool SerialLink::setPortName(QString portName)
     if(portName.trimmed().length() > 0)
     {
         bool reconnect = false;
-        if (port)
-        {
-            if (port->isOpen())
-            {
-                reconnect = true;
-            }
-            port->close();
-            delete port;
-        }
+        if (isConnected()) reconnect = true;
+        disconnect();
+
         this->porthandle = portName.trimmed();
         setName(tr("serial port ") + portName.trimmed());
 #ifdef _WIN32
@@ -614,14 +608,6 @@ bool SerialLink::setPortName(QString portName)
         }
 #endif
 
-        port = new QextSerialPort(porthandle, QextSerialPort::Polling);
-
-        port->setBaudRate(baudrate);
-        port->setFlowControl(flow);
-        port->setParity(parity);
-        port->setDataBits(dataBits);
-        port->setStopBits(stopBits);
-        port->setTimeout(timeout);
         if(reconnect) connect();
         return true;
     }
@@ -636,10 +622,9 @@ bool SerialLink::setBaudRateType(int rateIndex)
 {
     bool reconnect = false;
     bool accepted = true; // This is changed if none of the data rates matches
-    if(isConnected()) {
-        disconnect();
-        reconnect = true;
-    }
+    if(isConnected()) reconnect = true;
+    disconnect();
+
     switch (rateIndex) {
     case 0:
         baudrate = BAUD50;
@@ -722,9 +707,6 @@ bool SerialLink::setBaudRateType(int rateIndex)
         break;
     }
 
-    dataMutex.lock();
-    port->setBaudRate(this->baudrate);
-    dataMutex.unlock();
     if(reconnect) connect();
     return accepted;
 }
@@ -737,9 +719,9 @@ bool SerialLink::setBaudRate(int rate)
     bool accepted = true; // This is changed if none of the data rates matches
     if(isConnected())
     {
-        disconnect();
         reconnect = true;
     }
+    disconnect();
 
     switch (rate)
     {
@@ -824,27 +806,17 @@ bool SerialLink::setBaudRate(int rate)
         break;
     }
 
-    if (port)
-    {
-        port->setBaudRate(this->baudrate);
-        if(reconnect) connect();
-        return accepted;
-    }
-    else
-    {
-        return false;
-    }
+    if(reconnect) connect();
+    return accepted;
+
 }
 
 bool SerialLink::setFlowType(int flow)
 {
     bool reconnect = false;
     bool accepted = true;
-    if(isConnected())
-    {
-        disconnect();
-        reconnect = true;
-    }
+    if(isConnected()) reconnect = true;
+    disconnect();
 
     switch (flow)
     {
@@ -862,7 +834,7 @@ bool SerialLink::setFlowType(int flow)
         accepted = false;
         break;
     }
-    port->setFlowControl(this->flow);
+
     if(reconnect) connect();
     return accepted;
 }
@@ -871,27 +843,24 @@ bool SerialLink::setParityType(int parity)
 {
     bool reconnect = false;
     bool accepted = true;
-    if(isConnected())
-    {
-        disconnect();
-        reconnect = true;
-    }
+    if (isConnected()) reconnect = true;
+    disconnect();
 
     switch (parity)
     {
-    case PAR_NONE:
+    case (int)PAR_NONE:
         this->parity = PAR_NONE;
         break;
-    case PAR_ODD:
+    case (int)PAR_ODD:
         this->parity = PAR_ODD;
         break;
-    case PAR_EVEN:
+    case (int)PAR_EVEN:
         this->parity = PAR_EVEN;
         break;
-    case PAR_MARK:
+    case (int)PAR_MARK:
         this->parity = PAR_MARK;
         break;
-    case PAR_SPACE:
+    case (int)PAR_SPACE:
         this->parity = PAR_SPACE;
         break;
     default:
@@ -900,15 +869,17 @@ bool SerialLink::setParityType(int parity)
         break;
     }
 
-    port->setParity(this->parity);
-    if(reconnect) connect();
+    if (reconnect) connect();
     return accepted;
 }
 
 
 bool SerialLink::setDataBits(int dataBits)
 {
+    bool reconnect = false;
+    if (isConnected()) reconnect = true;
     bool accepted = true;
+    disconnect();
 
     switch (dataBits)
     {
@@ -930,11 +901,7 @@ bool SerialLink::setDataBits(int dataBits)
         break;
     }
 
-    port->setDataBits(this->dataBits);
-    if(isConnected()) {
-        disconnect();
-        connect();
-    }
+    if(reconnect) connect();
 
     return accepted;
 }
@@ -943,11 +910,8 @@ bool SerialLink::setStopBits(int stopBits)
 {
     bool reconnect = false;
     bool accepted = true;
-    if(isConnected())
-    {
-        disconnect();
-        reconnect = true;
-    }
+    if(isConnected()) reconnect = true;
+    disconnect();
 
     switch (stopBits)
     {
@@ -963,7 +927,6 @@ bool SerialLink::setStopBits(int stopBits)
         break;
     }
 
-    port->setStopBits(this->stopBits);
     if(reconnect) connect();
     return accepted;
 }
@@ -973,21 +936,14 @@ bool SerialLink::setDataBitsType(int dataBits)
     bool reconnect = false;
     bool accepted = false;
 
-    if (isConnected())
-    {
-        disconnect();
-        reconnect = true;
-    }
+    if (isConnected()) reconnect = true;
+    disconnect();
 
     if (dataBits >= (int)DATA_5 && dataBits <= (int)DATA_8)
     {
-        DataBitsType newBits = (DataBitsType) dataBits;
+        this->dataBits = (DataBitsType) dataBits;
 
-        port->setDataBits(newBits);
-        if(reconnect)
-        {
-            connect();
-        }
+        if(reconnect) connect();
         accepted = true;
     }
 
@@ -998,11 +954,8 @@ bool SerialLink::setStopBitsType(int stopBits)
 {
     bool reconnect = false;
     bool accepted = false;
-    if(isConnected())
-    {
-        disconnect();
-        reconnect = true;
-    }
+    if(isConnected()) reconnect = true;
+    disconnect();
 
     if (stopBits >= (int)STOP_1 && dataBits <= (int)STOP_2)
     {
diff --git a/src/uas/SlugsMAV.h b/src/uas/SlugsMAV.h
index 973d83e..50396a4 100644
--- a/src/uas/SlugsMAV.h
+++ b/src/uas/SlugsMAV.h
@@ -36,7 +36,7 @@ class SlugsMAV : public UAS
 public:
     SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
 
-
+    mavlink_pwm_commands_t* getPwmCommands();
 
 public slots:
     /** @brief Receive a MAVLink message from this MAV */
diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc
index 2fd26ce..8be801d 100644
--- a/src/ui/MainWindow.cc
+++ b/src/ui/MainWindow.cc
@@ -402,17 +402,17 @@ void MainWindow::buildPxWidgets()
 #ifdef QGC_OSG_ENABLED
     if (!_3DWidget)
     {
-        _3DWidget         = Q3DWidgetFactory::get("PIXHAWK");
-        addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
+//        _3DWidget         = Q3DWidgetFactory::get("PIXHAWK");
+//        addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
     }
 #endif
 
 #ifdef QGC_OSGEARTH_ENABLED
-    if (!_3DMapWidget)
-    {
-        _3DMapWidget = Q3DWidgetFactory::get("MAP3D");
-        addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
-    }
+//    if (!_3DMapWidget)
+//    {
+//        _3DMapWidget = Q3DWidgetFactory::get("MAP3D");
+//        addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
+//    }
 #endif
 
 #if (defined _MSC_VER) | (defined Q_OS_MAC)