Commit 80ad3802 authored by Lionel Heng's avatar Lionel Heng

Merge branch 'master' of github.com:mavlink/qgroundcontrol

parents c529ff51 8877827b
......@@ -84,16 +84,20 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
// Show user an upgrade message if QGC got upgraded (see code below, after splash screen)
bool upgraded = false;
QString lastApplicationVersion("");
if (settings.contains("QGC_APPLICATION_VERSION")) {
if (settings.contains("QGC_APPLICATION_VERSION"))
{
QString qgcVersion = settings.value("QGC_APPLICATION_VERSION").toString();
if (qgcVersion != QGC_APPLICATION_VERSION) {
if (qgcVersion != QGC_APPLICATION_VERSION)
{
lastApplicationVersion = qgcVersion;
settings.clear();
// Write current application version
settings.setValue("QGC_APPLICATION_VERSION", QGC_APPLICATION_VERSION);
upgraded = true;
}
} else {
}
else
{
// If application version is not set, clear settings anyway
settings.clear();
// Write current application version
......@@ -117,7 +121,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
// Load application font
QFontDatabase fontDatabase = QFontDatabase();
const QString fontFileName = ":/general/vera.ttf"; ///< Font file is part of the QRC file and compiled into the app
const QString fontFamilyName = "Bitstream Vera Sans";
//const QString fontFamilyName = "Bitstream Vera Sans";
if(!QFile::exists(fontFileName)) printf("ERROR! font file: %s DOES NOT EXIST!\n", fontFileName.toStdString().c_str());
fontDatabase.addApplicationFont(fontFileName);
// Avoid Using setFont(). In the Qt docu you can read the following:
......@@ -132,9 +136,6 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
splashScreen->showMessage(tr("Starting UAS Manager"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
startUASManager();
//tarsus = new ViconTarsusProtocol();
//tarsus->start();
// Start the user interface
splashScreen->showMessage(tr("Starting User Interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
// Start UI
......@@ -143,21 +144,18 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
// to make sure that all components are initialized when the
// first messages arrive
UDPLink* udpLink = new UDPLink(QHostAddress::Any, 14550);
MainWindow::instance()->addLink(udpLink);
MainWindow::instance()->addLink(udpLink);
// Listen on Multicast-Address 239.255.77.77, Port 14550
//QHostAddress * multicast_udp = new QHostAddress("239.255.77.77");
//UDPLink* udpLink = new UDPLink(*multicast_udp, 14550);
//mainWindow->addLink(udpLink);
#ifdef OPAL_RT
// Add OpalRT Link, but do not connect
OpalLink* opalLink = new OpalLink();
//mainWindow->addLink(opalLink);
MainWindow::instance()->addLink(opalLink);
#endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt");
simulationLink->disconnect();
//mainWindow->addLink(simulationLink);
mainWindow = MainWindow::instance(splashScreen);
......
......@@ -63,11 +63,16 @@ LinkManager::LinkManager()
LinkManager::~LinkManager()
{
disconnectAll();
foreach (LinkInterface* link, links)
{
if(link) link->deleteLater();
}
}
void LinkManager::add(LinkInterface* link)
{
if (!links.contains(link)) {
if (!links.contains(link))
{
if(!link) return;
connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
links.append(link);
......@@ -85,7 +90,8 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
// If protocol has not been added before (list length == 0)
// OR if link has not been added to protocol, add
if ((linkList.length() > 0 && !linkList.contains(link)) || linkList.length() == 0) {
if ((linkList.length() > 0 && !linkList.contains(link)) || linkList.length() == 0)
{
// Protocol is new, add
connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray)));
// Store the connection information in the protocol links map
......@@ -104,7 +110,8 @@ bool LinkManager::connectAll()
{
bool allConnected = true;
foreach (LinkInterface* link, links) {
foreach (LinkInterface* link, links)
{
if(!link) {}
else if(!link->connect()) allConnected = false;
}
......@@ -116,7 +123,8 @@ bool LinkManager::disconnectAll()
{
bool allDisconnected = true;
foreach (LinkInterface* link, links) {
foreach (LinkInterface* link, links)
{
//static int i=0;
if(!link) {}
else if(!link->disconnect()) allDisconnected = false;
......@@ -140,22 +148,27 @@ bool LinkManager::disconnectLink(LinkInterface* link)
void LinkManager::removeLink(QObject* link)
{
LinkInterface* linkInterface = dynamic_cast<LinkInterface*>(link);
if (linkInterface) {
if (linkInterface)
{
removeLink(linkInterface);
}
}
bool LinkManager::removeLink(LinkInterface* link)
{
if(link) {
for (int i=0; i < QList<LinkInterface*>(links).size(); i++) {
if(link==links.at(i)) {
if(link)
{
for (int i=0; i < QList<LinkInterface*>(links).size(); i++)
{
if(link==links.at(i))
{
links.removeAt(i); //remove from link list
}
}
// Remove link from protocol map
QList<ProtocolInterface* > protocols = protocolLinks.keys(link);
foreach (ProtocolInterface* proto, protocols) {
foreach (ProtocolInterface* proto, protocols)
{
protocolLinks.remove(proto, link);
}
return true;
......@@ -171,7 +184,8 @@ bool LinkManager::removeLink(LinkInterface* link)
*/
LinkInterface* LinkManager::getLinkForId(int id)
{
foreach (LinkInterface* link, links) {
foreach (LinkInterface* link, links)
{
if (link->getId() == id) return link;
}
return NULL;
......
......@@ -470,7 +470,7 @@ void MAVLinkProtocol::sendMessage(mavlink_message_t message)
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message)
{
// Create buffer
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Rewriting header to ensure correct link ID is set
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
......@@ -491,12 +491,14 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
*/
void MAVLinkProtocol::sendHeartbeat()
{
if (m_heartbeatsEnabled) {
if (m_heartbeatsEnabled)
{
mavlink_message_t beat;
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
sendMessage(beat);
}
if (m_authEnabled) {
if (m_authEnabled)
{
mavlink_message_t msg;
mavlink_auth_key_t auth;
if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN);
......
......@@ -84,15 +84,19 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
// Comments on the variables can be found in the header file
simulationFile = new QFile(readFile, this);
if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text)) {
if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text))
{
simulationHeader = simulationFile->readLine();
}
receiveFile = new QFile(writeFile, this);
lastSent = QGC::groundTimeMilliseconds();
if (simulationFile->exists()) {
if (simulationFile->exists())
{
this->name = "Simulation: " + QFileInfo(simulationFile->fileName()).fileName();
} else {
}
else
{
this->name = "MAVLink simulation link";
}
......@@ -111,6 +115,11 @@ MAVLinkSimulationLink::~MAVLinkSimulationLink()
//TODO Check destructor
// fileStream->flush();
// outStream->flush();
// Force termination, there is no
// need for cleanup since
// this thread is not manipulating
// any relevant data
terminate();
delete simulationFile;
}
......@@ -124,28 +133,26 @@ void MAVLinkSimulationLink::run()
system.custom_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED;
system.system_status = MAV_STATE_UNINIT;
forever {
forever
{
static quint64 last = 0;
if (QGC::groundTimeMilliseconds() - last >= rate) {
if (_isConnected) {
if (QGC::groundTimeMilliseconds() - last >= rate)
{
if (_isConnected)
{
mainloop();
// FIXME Hacky code to read from packet log file
// readyBufferMutex.lock();
// for (int i = 0; i < streampointer; i++)
// {
// readyBuffer.enqueue(*(stream + i));
// }
// readyBufferMutex.unlock();
readBytes();
}
else
{
// Sleep for substantially longer
// if not connected
QGC::SLEEP::msleep(500);
}
last = QGC::groundTimeMilliseconds();
}
QGC::SLEEP::msleep(3);
}
}
......@@ -157,7 +164,8 @@ void MAVLinkSimulationLink::sendMAVLinkMessage(const mavlink_message_t* msg)
// Pack to link buffer
readyBufferMutex.lock();
for (unsigned int i = 0; i < bufferlength; i++) {
for (unsigned int i = 0; i < bufferlength; i++)
{
readyBuffer.enqueue(*(buf + i));
}
readyBufferMutex.unlock();
......@@ -217,14 +225,17 @@ void MAVLinkSimulationLink::mainloop()
static int state = 0;
if (state == 0) {
if (state == 0)
{
state++;
}
// 50 HZ TASKS
if (rate50hzCounter == 1000 / rate / 40) {
if (simulationFile->isOpen()) {
if (rate50hzCounter == 1000 / rate / 40)
{
if (simulationFile->isOpen())
{
if (simulationFile->atEnd()) {
// We reached the end of the file, start from scratch
simulationFile->reset();
......@@ -916,7 +927,8 @@ void MAVLinkSimulationLink::readBytes()
bool MAVLinkSimulationLink::disconnect()
{
if(isConnected()) {
if(isConnected())
{
// timer->stop();
_isConnected = false;
......
......@@ -142,7 +142,8 @@ void UAS::readSettings()
this->name = settings.value("NAME", this->name).toString();
this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
if (settings.contains("BATTERY_SPECS")) {
if (settings.contains("BATTERY_SPECS"))
{
setBatterySpecs(settings.value("BATTERY_SPECS").toString());
}
settings.endGroup();
......@@ -1479,9 +1480,11 @@ void UAS::sendMessage(mavlink_message_t message)
// Emit message on all links that are currently connected
foreach (LinkInterface* link, *links)
{
qDebug() << "ITERATING THROUGH LINKS";
if (link)
{
sendMessage(link, message);
qDebug() << "SENT MESSAGE";
}
else
{
......@@ -1716,6 +1719,7 @@ void UAS::requestParameters()
mavlink_message_t msg;
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
sendMessage(msg);
qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST";
}
void UAS::writeParametersToStorage()
......
......@@ -234,8 +234,21 @@ MainWindow::MainWindow(QWidget *parent):
MainWindow::~MainWindow()
{
delete mavlink;
delete joystick;
if (mavlink)
{
delete mavlink;
mavlink = NULL;
}
// if (simulationLink)
// {
// simulationLink->deleteLater();
// simulationLink = NULL;
// }
if (joystick)
{
delete joystick;
joystick = NULL;
}
// Get and delete all dockwidgets and contained
// widgets
......@@ -252,10 +265,12 @@ MainWindow::~MainWindow()
// removeDockWidget(dockWidget);
// delete dockWidget->widget();
delete dockWidget;
dockWidget = NULL;
}
else if (dynamic_cast<QObject*>(*i))
else if (dynamic_cast<QWidget*>(*i))
{
delete dynamic_cast<QObject*>(*i);
delete dynamic_cast<QWidget*>(*i);
*i = NULL;
}
}
// Delete all UAS objects
......
......@@ -95,23 +95,27 @@ public:
static MainWindow* instance(QSplashScreen* screen = 0);
~MainWindow();
enum QGC_MAINWINDOW_STYLE {
enum QGC_MAINWINDOW_STYLE
{
QGC_MAINWINDOW_STYLE_NATIVE,
QGC_MAINWINDOW_STYLE_INDOOR,
QGC_MAINWINDOW_STYLE_OUTDOOR
};
/** @brief Get current visual style */
int getStyle() {
int getStyle()
{
return currentStyle;
}
/** @brief Get auto link reconnect setting */
bool autoReconnectEnabled() {
bool autoReconnectEnabled()
{
return autoReconnect;
}
/** @brief Get low power mode setting */
bool lowPowerModeEnabled() {
bool lowPowerModeEnabled()
{
return lowPowerMode;
}
......
......@@ -590,7 +590,6 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
*/
void QGCParamWidget::requestParameterList()
{
qDebug() << "LOADING PARAM LIST";
if (!mav) return;
// FIXME This call does not belong here
// Once the comm handling is moved to a new
......@@ -606,7 +605,8 @@ void QGCParamWidget::requestParameterList()
// Clear transmission state
transmissionListMode = true;
transmissionListSizeKnown.clear();
foreach (int key, transmissionMissingPackets.keys()) {
foreach (int key, transmissionMissingPackets.keys())
{
transmissionMissingPackets.value(key)->clear();
}
transmissionActive = true;
......
......@@ -80,6 +80,7 @@ QGCCommandButton::QGCCommandButton(QWidget *parent) :
ui->editCommandComboBox->addItem("MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN", MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN);
ui->editCommandComboBox->addItem("MAV_CMD_OVERRIDE_GOTO", MAV_CMD_OVERRIDE_GOTO);
ui->editCommandComboBox->addItem("MAV_CMD_MISSION_START", MAV_CMD_MISSION_START);
ui->editCommandComboBox->addItem("MAV_CMD_COMPONENT_ARM_DISARM", MAV_CMD_COMPONENT_ARM_DISARM);
ui->editCommandComboBox->setEditable(true);
}
......@@ -136,6 +137,7 @@ void QGCCommandButton::startEditMode()
ui->commandButton->hide();
ui->nameLabel->hide();
ui->editCommandComboBox->blockSignals(false);
ui->editCommandComboBox->show();
ui->editFinishButton->show();
ui->editNameLabel->show();
......@@ -158,6 +160,7 @@ void QGCCommandButton::startEditMode()
void QGCCommandButton::endEditMode()
{
ui->editCommandComboBox->blockSignals(true);
ui->editCommandComboBox->hide();
ui->editFinishButton->hide();
ui->editNameLabel->hide();
......
......@@ -283,7 +283,8 @@ enum MAV_CMD
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_ENUM_END=301, /* | */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
MAV_CMD_ENUM_END=401, /* | */
};
#endif
......
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Feb 25 17:32:04 2012"
#define MAVLINK_BUILD_DATE "Sun Feb 26 16:49:33 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Feb 25 17:32:04 2012"
#define MAVLINK_BUILD_DATE "Sun Feb 26 16:49:33 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -668,6 +668,10 @@
<param index="1">first_item: the first mission item to run</param>
<param index="2">last_item: the last mission item to run (after this item is run, the mission ends)</param>
</entry>
<entry value="400" name="MAV_CMD_COMPONENT_ARM_DISARM">
<description>Arms / Disarms a component</description>
<param index="1">1 to arm, 0 to disarm</param>
</entry>
</enum>
<enum name="MAV_DATA_STREAM">
<description>Data stream IDs. A data stream is not a fixed set of messages, but rather a
......
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