Commit 38941da9 authored by pixhawk's avatar pixhawk

Added new options for windows serial port, fixed a number of bugs, added...

Added new options for windows serial port, fixed a number of bugs, added customizing options to instrument widgets
parent fd99a0e0
......@@ -12,6 +12,7 @@ cp -r ../bin/mac/qgroundcontrol.app mac/.
cp -r ../audio mac/qgroundcontrol.app/Contents/MacOs/.
mkdir -p mac/qgroundcontrol.app/Contents/Frameworks/
# SDL is not copied by Qt - for whatever reason
cp -r SDL.framework mac/qgroundcontrol.app/Contents/Frameworks/.
echo -e '\n\nStarting to create disk image. This may take a while..\n'
macdeployqt mac/qgroundcontrol.app -dmg
......
......@@ -29,6 +29,7 @@
# $$BASEDIR/lib/openjaus/libopenJaus/include
message(Qt version $$[QT_VERSION])
message(Using Qt from $QTDIR)
release {
# DEFINES += QT_NO_DEBUG_OUTPUT
......@@ -50,6 +51,7 @@ macx {
contains( HARDWARE_PLATFORM, 9.6.0 ) || contains( HARDWARE_PLATFORM, 9.7.0 ) || contains( HARDWARE_PLATFORM, 9.8.0 ) || contains( HARDWARE_PLATFORM, 9.9.0 ) {
# x86 Mac OS X Leopard 10.5 and earlier
CONFIG += x86 cocoa phonon
CONFIG -= x86_64
message(Building for Mac OS X 32bit/Leopard 10.5 and earlier)
# Enable function-profiling with the OS X saturn tool
......
......@@ -11,6 +11,7 @@ namespace QGC
const QColor colorGreen(20, 200, 20);
const QColor colorYellow(255, 255, 0);
const QColor colorDarkYellow(180, 180, 0);
const QColor colorBackground("#050508");
/** @brief Get the current ground time in microseconds */
quint64 groundTimeUsecs();
......
......@@ -289,16 +289,19 @@ void MAVLinkSimulationLink::mainloop()
if (keys.value(i, "") == "Gyro_Phi")
{
rawImuValues.xgyro = d;
attitude.rollspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
}
if (keys.value(i, "") == "Gyro_Theta")
{
rawImuValues.ygyro = d;
attitude.pitchspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
}
if (keys.value(i, "") == "Gyro_Psi")
{
rawImuValues.zgyro = d;
attitude.yawspeed = ((d-29.000)/3000.0)*2.7-2.7-2.65;
}
#ifdef MAVLINK_ENABLED_PIXHAWK
if (keys.value(i, "") == "Pressure")
......@@ -426,12 +429,12 @@ void MAVLinkSimulationLink::mainloop()
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// GLOBAL POSITION VEHICLE 3
mavlink_msg_global_position_int_pack(60, componentId, &ret, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// // GLOBAL POSITION VEHICLE 3
// mavlink_msg_global_position_int_pack(60, componentId, &ret, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
// bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
// //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength);
// streampointer += bufferlength;
static int rcCounter = 0;
if (rcCounter == 2)
......@@ -609,15 +612,15 @@ void MAVLinkSimulationLink::mainloop()
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// HEARTBEAT VEHICLE 3
// // HEARTBEAT VEHICLE 3
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// // Pack message and get size of encoded byte string
// messageSize = mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// // Allocate buffer with packet data
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength);
// streampointer += bufferlength;
// STATUS VEHICLE 2
mavlink_sys_status_t status2;
......
/*=====================================================================
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/>.
======================================================================*/
/**
* @file
......@@ -58,34 +38,16 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
// Load defaults from settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.sync();
if (settings.contains("SERIALLINK_COMM_PORT"))
{
this->porthandle = settings.value("SERIALLINK_COMM_PORT").toString();
}
// *nix (Linux, MacOS tested) serial port support
port = new QextSerialPort(porthandle, QextSerialPort::Polling);
//port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
if (settings.contains("SERIALLINK_COMM_PORT"))
{
setBaudRate(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
setDataBitsType(settings.value("SERIALLINK_COMM_DATABITS").toInt());
}
else
{
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
}
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
port->setBaudRate(baudrate);
port->setFlowControl(flow);
......@@ -96,7 +58,7 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
// Set the port name
if (porthandle == "")
{
// name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)");
// name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)");
name = tr("Serial Link ") + QString::number(getId());
}
else
......@@ -134,6 +96,33 @@ SerialLink::~SerialLink()
port = NULL;
}
void SerialLink::loadSettings()
{
// Load defaults from settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.sync();
if (settings.contains("SERIALLINK_COMM_PORT"))
{
setPortName(settings.value("SERIALLINK_COMM_PORT").toString());
setBaudRateType(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
setDataBitsType(settings.value("SERIALLINK_COMM_DATABITS").toInt());
}
}
void SerialLink::writeSettings()
{
// Store settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
settings.setValue("SERIALLINK_COMM_BAUD", getBaudRateType());
settings.setValue("SERIALLINK_COMM_PARITY", getParityType());
settings.setValue("SERIALLINK_COMM_STOPBITS", getStopBitsType());
settings.setValue("SERIALLINK_COMM_DATABITS", getDataBitsType());
settings.sync();
}
/**
* @brief Runs the thread
......@@ -189,13 +178,13 @@ void SerialLink::writeBytes(const char* data, qint64 size)
// Increase write counter
bitsSentTotal += size * 8;
// int i;
// for (i=0; i<size; i++)
// {
// unsigned char v=data[i];
// int i;
// for (i=0; i<size; i++)
// {
// unsigned char v=data[i];
// //fprintf(stderr,"%02x ", v);
// }
// //fprintf(stderr,"%02x ", v);
// }
}
}
......@@ -321,18 +310,12 @@ bool SerialLink::hardwareConnect()
statisticsMutex.unlock();
bool connectionUp = isConnected();
if(connectionUp) {
if(connectionUp)
{
emit connected();
emit connected(true);
// Store settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
settings.setValue("SERIALLINK_COMM_BAUD", getBaudRate());
settings.setValue("SERIALLINK_COMM_PARITY", getParityType());
settings.setValue("SERIALLINK_COMM_STOPBITS", getStopBitsType());
settings.setValue("SERIALLINK_COMM_DATABITS", getDataBitsType());
settings.sync();
writeSettings();
}
return connectionUp;
......@@ -376,7 +359,8 @@ void SerialLink::setName(QString name)
qint64 SerialLink::getNominalDataRate()
{
qint64 dataRate = 0;
switch (baudrate) {
switch (baudrate)
{
case BAUD50:
dataRate = 50;
break;
......@@ -442,6 +426,13 @@ qint64 SerialLink::getNominalDataRate()
break;
case BAUD256000:
dataRate = 256000;
// Windows-specific high-end baudrates
case BAUD230400:
dataRate = 230400;
case BAUD460800:
dataRate = 460800;
case BAUD921600:
dataRate = 921600;
break;
}
return dataRate;
......@@ -543,7 +534,8 @@ bool SerialLink::setPortName(QString portName)
if(portName.trimmed().length() > 0)
{
bool reconnect = false;
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
......@@ -650,8 +642,17 @@ bool SerialLink::setBaudRateType(int rateIndex)
baudrate = BAUD128000;
break;
case 21:
baudrate = BAUD230400;
break;
case 22:
baudrate = BAUD256000;
break;
case 23:
baudrate = BAUD460800;
break;
case 24:
baudrate = BAUD921600;
break;
default:
// If none of the above cases matches, there must be an error
accepted = false;
......@@ -671,12 +672,14 @@ bool SerialLink::setBaudRate(int rate)
{
bool reconnect = false;
bool accepted = true; // This is changed if none of the data rates matches
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
switch (rate) {
switch (rate)
{
case 50:
baudrate = BAUD50;
break;
......@@ -740,9 +743,18 @@ bool SerialLink::setBaudRate(int rate)
case 128000:
baudrate = BAUD128000;
break;
case 230400:
baudrate = BAUD230400;
break;
case 256000:
baudrate = BAUD256000;
break;
case 460800:
baudrate = BAUD460800;
break;
case 921600:
baudrate = BAUD921600;
break;
default:
// If none of the above cases matches, there must be an error
accepted = false;
......@@ -765,12 +777,14 @@ bool SerialLink::setFlowType(int flow)
{
bool reconnect = false;
bool accepted = true;
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
switch (flow) {
switch (flow)
{
case FLOW_OFF:
this->flow = FLOW_OFF;
break;
......@@ -794,12 +808,14 @@ bool SerialLink::setParityType(int parity)
{
bool reconnect = false;
bool accepted = true;
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
switch (parity) {
switch (parity)
{
case PAR_NONE:
this->parity = PAR_NONE;
break;
......@@ -826,11 +842,14 @@ bool SerialLink::setParityType(int parity)
return accepted;
}
// FIXME Works not as anticipated by user!
bool SerialLink::setDataBitsType(int dataBits)
{
bool accepted = true;
switch (dataBits) {
switch (dataBits)
{
case 5:
this->dataBits = DATA_5;
break;
......@@ -858,6 +877,7 @@ bool SerialLink::setDataBitsType(int dataBits)
return accepted;
}
// FIXME WORKS NOT AS ANTICIPATED BY USER!
bool SerialLink::setStopBitsType(int stopBits)
{
bool reconnect = false;
......@@ -867,7 +887,8 @@ bool SerialLink::setStopBitsType(int stopBits)
reconnect = true;
}
switch (stopBits) {
switch (stopBits)
{
case 1:
this->stopBits = STOP_1;
break;
......
......@@ -91,6 +91,9 @@ public:
qint64 getBitsSent();
qint64 getBitsReceived();
void loadSettings();
void writeSettings();
void run();
int getLinkQuality();
......
......@@ -57,6 +57,8 @@ public slots:
virtual bool setParityType(int parity) = 0;
virtual bool setDataBitsType(int dataBits) = 0;
virtual bool setStopBitsType(int stopBits) = 0;
virtual void loadSettings() = 0;
virtual void writeSettings() = 0;
};
......
......@@ -92,8 +92,11 @@ enum BaudRateType
BAUD57600,
BAUD76800, //POSIX ONLY
BAUD115200,
BAUD128000, //WINDOWS ONLY
BAUD256000 //WINDOWS ONLY
BAUD128000, // WINDOWS ONLY
BAUD230400, // WINDOWS ONLY
BAUD256000, // WINDOWS ONLY
BAUD460800, // WINDOWS ONLY
BAUD921600 // WINDOWS ONLY
};
enum DataBitsType
......
This diff is collapsed.
This diff is collapsed.
......@@ -37,6 +37,7 @@ This file is part of the QGROUNDCONTROL project
#include <QTimer>
#include <QFontDatabase>
#include <QMap>
#include <QContextMenuEvent>
#include <QPair>
#include <cmath>
......@@ -58,14 +59,31 @@ class HDDisplay : public QGraphicsView
{
Q_OBJECT
public:
HDDisplay(QStringList* plotList, QWidget *parent = 0);
HDDisplay(QStringList* plotList, QString title="", QWidget *parent = 0);
~HDDisplay();
public slots:
/** @brief Update a HDD value */
void updateValue(UASInterface* uas, QString name, double value, quint64 msec);
void updateValue(int uasId, QString name, double value, quint64 msec);
void setActiveUAS(UASInterface* uas);
/** @brief Removes a plot item by the action data */
void removeItemByAction();
/** @brief Bring up the menu to add a gauge */
void addGauge();
/** @brief Add a gauge using this spec string */
void addGauge(const QString& gauge);
/** @brief Set the title of this widget and any existing parent dock widget */
void setTitle();
/** @brief Set the number of colums via popup */
void setColumns();
/** @brief Set the number of colums */
void setColumns(int cols);
/** @brief Save the current layout and state to disk */
void saveState();
/** @brief Restore the last layout and state from disk */
void restoreState();
protected slots:
void enableGLRendering(bool enable);
//void render(QPainter* painter, const QRectF& target = QRectF(), const QRect& source = QRect(), Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio);
......@@ -73,10 +91,13 @@ protected slots:
void triggerUpdate();
protected:
void changeEvent(QEvent *e);
void paintEvent(QPaintEvent * event);
void changeEvent(QEvent* e);
void paintEvent(QPaintEvent* event);
void showEvent(QShowEvent* event);
void hideEvent(QHideEvent* event);
void contextMenuEvent(QContextMenuEvent* event);
QList<QAction*> getItemRemoveActions();
void createActions();
float refLineWidthToPen(float line);
float refToScreenX(float x);
float refToScreenY(float y);
......@@ -155,6 +176,11 @@ protected:
QStringList* acceptList; ///< Variable names to plot
quint64 lastPaintTime; ///< Last time this widget was refreshed
int columns; ///< Number of instrument columns
QAction* addGaugeAction; ///< Action adding a gauge
QAction* setTitleAction; ///< Action setting the title
QAction* setColumnsAction; ///< Action setting the number of columns
private:
Ui::HDDisplay *m_ui;
......
......@@ -46,7 +46,7 @@ This file is part of the QGROUNDCONTROL project
#include <QDebug>
HSIDisplay::HSIDisplay(QWidget *parent) :
HDDisplay(NULL, parent),
HDDisplay(NULL, "", parent),
gpsSatellites(),
satellitesUsed(0),
attXSet(0),
......
......@@ -207,17 +207,19 @@ void MainWindow::buildPxWidgets()
{
//FIXME: memory of acceptList will never be freed again
QStringList* acceptList = new QStringList();
acceptList->append("roll IMU");
acceptList->append("pitch IMU");
acceptList->append("yaw IMU");
acceptList->append("rollspeed IMU");
acceptList->append("pitchspeed IMU");
acceptList->append("yawspeed IMU");
acceptList->append("-180,roll (deg),+180");
acceptList->append("-180,pitch (deg),+180");
acceptList->append("-180,yaw (deg),+180");
acceptList->append("-500,roll V (deg/s),+500");
acceptList->append("-500,pitch V (deg/s),+500");
acceptList->append("-500,yaw V (deg/s),+500");
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList();
acceptList2->append("Battery");
acceptList2->append("Pressure");
acceptList2->append("0,Abs pressure,65500");
acceptList2->append("-2000,Accel. X, 2000");
acceptList2->append("-2000,Accel. Y, 2000");
if (!linechartWidget)
{
......@@ -296,15 +298,15 @@ void MainWindow::buildPxWidgets()
if (!headDown1DockWidget)
{
headDown1DockWidget = new QDockWidget(tr("System Stats"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
headDown1DockWidget = new QDockWidget(tr("Flight Display"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, "Flight Display", this) );
addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea);
}
if (!headDown2DockWidget)
{
headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, "Payload Status", this) );
addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget()), MENU_HDD_2, Qt::RightDockWidgetArea);
}
......
......@@ -234,6 +234,7 @@ userConfigured(false)
if(serialLink != 0)
{
serialLink->loadSettings();
this->link = serialLink;
// Setup the user interface according to link type
......
......@@ -159,11 +159,26 @@
<string>128000</string>
</property>
</item>
<item>
<property name="text">
<string>230400</string>
</property>
</item>
<item>
<property name="text">
<string>256000</string>
</property>
</item>
<item>
<property name="text">
<string>460800</string>
</property>
</item>
<item>
<property name="text">
<string>921600</string>
</property>
</item>
</widget>
</item>
<item row="2" column="0">
......
......@@ -72,7 +72,7 @@ public:
public slots:
void addCurve(QString curve);
void removeCurve(QString curve);
void appendData(int sysId, QString curve, double data, quint64 usec);
void appendData(int uasId, QString curve, double data, quint64 usec);
void takeButtonClick(bool checked);
void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position);
......
......@@ -231,7 +231,7 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event)
// Reloading the webpage, this resets Google Earth
gEarthInitialized = false;
QTimer::singleShot(3000, this, SLOT(initializeGoogleEarth()));
QTimer::singleShot(10000, this, SLOT(initializeGoogleEarth()));
}
else
{
......@@ -300,7 +300,7 @@ void QGCGoogleEarthView::initializeGoogleEarth()
qDebug() << "COULD NOT GET DOCUMENT OBJECT! Aborting";
}
#endif
QTimer::singleShot(3500, this, SLOT(initializeGoogleEarth()));
QTimer::singleShot(2500, this, SLOT(initializeGoogleEarth()));
return;
}
......
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