Commit 1b1e7a36 authored by Mariano Lizarraga's avatar Mariano Lizarraga

Merge branch 'master' of git@pixhawk.ethz.ch:qgroundcontrol into checkRemote

parents 2f111432 9e35225b
......@@ -73,7 +73,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/watchdog/WatchdogProcessView.ui \
src/ui/watchdog/WatchdogView.ui \
src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -149,7 +150,10 @@ HEADERS += src/MG.h \
src/ui/HSIDisplay.h \
src/QGC.h \
src/ui/QGCFirmwareUpdate.h \
src/ui/QGCPxImuFirmwareUpdate.h
src/ui/QGCPxImuFirmwareUpdate.h \
src/comm/MAVLinkLightProtocol.h \
src/ui/QGCDataPlot2D.h \
src/ui/linechart/IncrementalPlot.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -207,5 +211,8 @@ SOURCES += src/main.cc \
src/ui/HSIDisplay.cc \
src/QGC.cc \
src/ui/QGCFirmwareUpdate.cc \
src/ui/QGCPxImuFirmwareUpdate.cc
src/ui/QGCPxImuFirmwareUpdate.cc \
src/comm/MAVLinkLightProtocol.cc \
src/ui/QGCDataPlot2D.cc \
src/ui/linechart/IncrementalPlot.cc
RESOURCES = mavground.qrc
#include <QFile>
#include <QTextStream>
#include <QStringList>
#include <QFileInfo>
#include "LogCompressor.h"
#include <QDebug>
LogCompressor::LogCompressor(QString logFileName, int uasid) :
LogCompressor::LogCompressor(QString logFileName, QString outFileName, int uasid) :
logFileName(logFileName),
outFileName(outFileName),
running(true),
currentDataLine(0),
dataLines(1),
uasid(uasid)
{
start();
......@@ -17,13 +22,23 @@ void LogCompressor::run()
QString separator = "\t";
QString fileName = logFileName;
QFile file(fileName);
QFile outfile(outFileName);
QStringList* keys = new QStringList();
QStringList* times = new QStringList();
if (!file.exists()) return;
if (!file.open(QIODevice::ReadWrite | QIODevice::Text))
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
return;
if (outFileName != "")
{
// Check if file is writeable
if (!QFileInfo(outfile).isWritable())
{
return;
}
}
// Find all keys
QTextStream in(&file);
while (!in.atEnd()) {
......@@ -43,9 +58,9 @@ void LogCompressor::run()
spacer += " " + separator;
}
qDebug() << header;
//qDebug() << header;
qDebug() << "NOW READING TIMES";
//qDebug() << "NOW READING TIMES";
// Find all times
//in.reset();
......@@ -62,6 +77,9 @@ void LogCompressor::run()
times->append(time);
}
}
dataLines = times->length();
times->sort();
// Create lines
......@@ -74,7 +92,10 @@ void LogCompressor::run()
// Fill in the values for all keys
file.reset();
QTextStream data(&file);
int linecounter = 0;
while (!data.atEnd()) {
linecounter++;
currentDataLine = linecounter;
QString line = data.readLine();
QStringList parts = line.split(separator);
// Get time
......@@ -100,20 +121,43 @@ void LogCompressor::run()
// Add header, write out file
file.close();
QFile::remove(file.fileName());
if (!file.open(QIODevice::ReadWrite | QIODevice::Text))
if (outFileName == "")
{
QFile::remove(file.fileName());
outfile.setFileName(file.fileName());
}
if (!outfile.open(QIODevice::WriteOnly | QIODevice::Text))
return;
file.write(QString(QString("unix_timestamp") + separator + header.replace(" ", "_") + QString("\n")).toLatin1());
outfile.write(QString(QString("unix_timestamp") + separator + header.replace(" ", "_") + QString("\n")).toLatin1());
//QString fileHeader = QString("unix_timestamp") + header.replace(" ", "_") + QString("\n");
// Debug output
// File output
for (int i = 0; i < outLines->length(); i++)
{
//qDebug() << outLines->at(i);
file.write(QString(outLines->at(i) + "\n").toLatin1());
outfile.write(QString(outLines->at(i) + "\n").toLatin1());
}
currentDataLine = 0;
dataLines = 1;
delete keys;
qDebug() << "Done with logfile processing";
running = false;
}
bool LogCompressor::isFinished()
{
return !running;
}
int LogCompressor::getCurrentLine()
{
return currentDataLine;
}
int LogCompressor::getDataLines()
{
return dataLines;
}
......@@ -6,10 +6,17 @@
class LogCompressor : public QThread
{
public:
LogCompressor(QString logFileName, int uasid = 0);
LogCompressor(QString logFileName, QString outFileName="", int uasid = 0);
bool isFinished();
int getDataLines();
int getCurrentLine();
protected:
void run();
QString logFileName;
QString outFileName;
bool running;
int currentDataLine;
int dataLines;
int uasid;
};
......
......@@ -31,6 +31,7 @@ This file is part of the PIXHAWK project
*/
#include "Waypoint.h"
#include <QStringList>
Waypoint::Waypoint(quint16 _id, float _x, float _y, float _z, float _yaw, bool _autocontinue, bool _current, float _orbit, int _holdTime)
: id(_id),
......@@ -50,6 +51,30 @@ Waypoint::~Waypoint()
}
void Waypoint::save(QTextStream &saveStream)
{
saveStream << "\t" << this->getId() << "\t" << this->getX() << "\t" << this->getY() << "\t" << this->getZ() << "\t" << this->getYaw() << "\t" << this->getAutoContinue() << "\t" << this->getCurrent() << "\t" << this->getOrbit() << "\t" << this->getHoldTime() << "\n";
}
bool Waypoint::load(QTextStream &loadStream)
{
const QStringList &wpParams = loadStream.readLine().split("\t");
if (wpParams.size() == 10)
{
this->id = wpParams[1].toInt();
this->x = wpParams[2].toDouble();
this->y = wpParams[3].toDouble();
this->z = wpParams[4].toDouble();
this->yaw = wpParams[5].toDouble();
this->autocontinue = (wpParams[6].toInt() == 1 ? true : false);
this->current = (wpParams[7].toInt() == 1 ? true : false);
this->orbit = wpParams[8].toDouble();
this->holdTime = wpParams[9].toInt();
return true;
}
return false;
}
void Waypoint::setId(quint16 id)
{
this->id = id;
......
......@@ -35,6 +35,7 @@ This file is part of the PIXHAWK project
#include <QObject>
#include <QString>
#include <QTextStream>
class Waypoint : public QObject
{
......@@ -54,6 +55,10 @@ public:
float getOrbit() const { return orbit; }
float getHoldTime() const { return holdTime; }
void save(QTextStream &saveStream);
bool load(QTextStream &loadStream);
private:
quint16 id;
float x;
......
/*=====================================================================
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
* @brief Example implementation of a different protocol than the default MAVLink.
* @author Lorenz Meier <mail@qgroundcontrol.org>
*/
#include "MAVLinkLightProtocol.h"
#include "UASManager.h"
#include "ArduPilotMAV.h"
#include "LinkManager.h"
MAVLinkLightProtocol::MAVLinkLightProtocol() :
MAVLinkProtocol()
{
}
/**
* @param message message to send
*/
void MAVLinkLightProtocol::sendMessage(mavlink_light_message_t message)
{
// Get all links connected to this unit
QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);
// Emit message on all links that are currently connected
QList<LinkInterface*>::iterator i;
for (i = links.begin(); i != links.end(); ++i)
{
sendMessage(*i, message);
}
}
/**
* @param link the link to send the message over
* @param message message to send
*/
void MAVLinkLightProtocol::sendMessage(LinkInterface* link, mavlink_light_message_t message)
{
// Create buffer
uint8_t buffer[100]; // MAXIMUM PACKET LENGTH, INCLUDING STX BYTES
// Write message into buffer, prepending start sign
//int len = mavlink_msg_to_send_buffer(buffer, &message);
// FIXME TO SEND BUFFER FUNCTION MISSING
Q_UNUSED(message);
int len = 0;
// If link is connected
if (link->isConnected())
{
// Send the portion of the buffer now occupied by the message
link->writeBytes((const char*)buffer, len);
}
}
/**
* The bytes are copied by calling the LinkInterface::readBytes() method.
* This method parses all incoming bytes and constructs a MAVLink packet.
* It can handle multiple links in parallel, as each link has it's own buffer/
* parsing state machine.
* @param link The interface to read from
* @see LinkInterface
**/
void MAVLinkLightProtocol::receiveBytes(LinkInterface* link)
{
receiveMutex.lock();
// Prepare buffer
static const int maxlen = 4096 * 100;
static char buffer[maxlen];
qint64 bytesToRead = link->bytesAvailable();
// Get all data at once, let link read the bytes in the buffer array
link->readBytes(buffer, maxlen);
// Run through all bytes
for (int position = 0; position < bytesToRead; position++)
{
mavlink_light_message_t msg;
// FIXME PARSE
if (1 == 0/* parsing returned a message */)
{
int sysid = 0; // system id from message, or always null if only one MAV is supported
UASInterface* uas = UASManager::instance()->getUASForId(sysid);
// Check and (if necessary) create UAS object
if (uas == NULL)
{
ArduPilotMAV* mav = new ArduPilotMAV(this, sysid); // FIXME change to msg.sysid if this field exists
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
// Make UAS aware that this link can be used to communicate with the actual robot
uas->addLink(link);
// Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uas);
}
// The packet is emitted as a whole, as it is only 255 - 261 bytes short
// kind of inefficient, but no issue for a groundstation pc.
// It buys as reentrancy for the whole code over all threads
emit messageReceived(link, msg);
}
}
receiveMutex.unlock();
}
/**
* @return The name of this protocol
**/
QString MAVLinkLightProtocol::getName()
{
return QString(tr("MAVLinkLight protocol"));
}
/*=====================================================================
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
* @brief Example implementation of a different protocol than the default MAVLink.
* @author Lorenz Meier <mail@qgroundcontrol.org>
*/
#ifndef MAVLINKLIGHTPROTOCOL_H
#define MAVLINKLIGHTPROTOCOL_H
#include <inttypes.h>
#include <MAVLinkProtocol.h>
#define MAVLINK_LIGHT_MAX_PAYLOAD_LEN 50
// Not part of message struct, but sent on link
// uint8_t stx1;
// uint8_t stx2;
typedef struct {
uint8_t msgid; ///< ID of message in payload
uint8_t payload[MAVLINK_LIGHT_MAX_PAYLOAD_LEN]; ///< Payload data, ALIGNMENT IMPORTANT ON MCU
uint8_t ck_a; ///< Checksum high byte
uint8_t ck_b; ///< Checksum low byte
} mavlink_light_message_t;
class MAVLinkLightProtocol : public MAVLinkProtocol
{
Q_OBJECT
public:
explicit MAVLinkLightProtocol();
QString getName();
signals:
/** @brief Message received and directly copied via signal */
void messageReceived(LinkInterface* link, mavlink_light_message_t message);
public slots:
void sendMessage(mavlink_light_message_t message);
void sendMessage(LinkInterface* link, mavlink_light_message_t message);
void receiveBytes(LinkInterface* link);
};
#endif // MAVLINKLIGHTPROTOCOL_H
......@@ -323,7 +323,7 @@ void MAVLinkProtocol::sendMessage(mavlink_message_t message)
for (i = links.begin(); i != links.end(); ++i)
{
sendMessage(*i, message);
qDebug() << __FILE__ << __LINE__ << "SENT HEARTBEAT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
//qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
}
}
......
......@@ -186,10 +186,13 @@ void MAVLinkSimulationLink::mainloop()
static float drainRate = 0.025; // x.xx% of the capacity is linearly drained per second
mavlink_attitude_t attitude;
memset(&attitude, 0, sizeof(mavlink_attitude_t));
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_raw_aux_t rawAuxValues;
memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
#endif
mavlink_raw_imu_t rawImuValues;
memset(&rawImuValues, 0, sizeof(mavlink_raw_imu_t));
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int bufferlength;
......
/*=====================================================================
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
* @brief Implementation of class MainWindow
* @author Your Name here
*/
#include "ArduPilotMAV.h"
ArduPilotMAV::ArduPilotMAV(MAVLinkProtocol* mavlink, int id) :
......
......@@ -131,8 +131,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id)
{
//update the UI FIXME
emit waypointUpdated(wp->seq, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue, wp->current, wp->param1, wp->param2);
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue, wp->current, wp->param1, wp->param2);
localAddWaypoint(lwp);
//get next waypoint
current_wp_id++;
......@@ -223,42 +223,182 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
{
protocol_timer.stop();
current_state = WP_IDLE;
// update the local main storage
if (wpc->seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
if (waypoints[i]->getId() == wpc->seq)
{
waypoints[i]->setCurrent(true);
}
else
{
waypoints[i]->setCurrent(false);
}
}
}
emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
//emit update to UI widgets
emit currentWaypointChanged(wpc->seq);
}
qDebug() << "new current waypoint" << wpc->seq;
emit currentWaypointChanged(wpc->seq);
}
}
void UASWaypointManager::clearWaypointList()
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
{
if(current_state == WP_IDLE)
if (seq < waypoints.size())
{
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
if(current_state == WP_IDLE)
{
//update local main storage
for(int i = 0; i < waypoints.size(); i++)
{
if (waypoints[i]->getId() == seq)
{
waypoints[i]->setCurrent(true);
}
else
{
waypoints[i]->setCurrent(false);
}
}
current_state = WP_CLEARLIST;
current_wp_id = 0;
current_partner_systemid = uas.getUASID();
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
//TODO: signal changed waypoint list
sendWaypointClearAll();
//send change to UAS - important to note: if the transmission fails, we have inconsistencies
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_SETCURRENT;
current_wp_id = seq;
current_partner_systemid = uas.getUASID();
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
sendWaypointSetCurrent(current_wp_id);
//emit waypointListChanged();
return 0;
}
}
return -1;
}
void UASWaypointManager::localAddWaypoint(Waypoint *wp)
{
if (wp)
{
wp->setId(waypoints.size());
waypoints.insert(waypoints.size(), wp);
emit waypointListChanged();
}
}
void UASWaypointManager::setCurrent(quint16 seq)
int UASWaypointManager::localRemoveWaypoint(quint16 seq)
{
if (seq < waypoints.size())
{
Waypoint *t = waypoints[seq];
waypoints.remove(seq);
delete t;
for(int i = seq; i < waypoints.size(); i++)
{
waypoints[i]->setId(i);
}
emit waypointListChanged();
return 0;
}
return -1;
}
void UASWaypointManager::localMoveWaypoint(quint16 cur_seq, quint16 new_seq)
{
if (cur_seq != new_seq && cur_seq < waypoints.size() && new_seq < waypoints.size())
{
Waypoint *t = waypoints[cur_seq];
if (cur_seq < new_seq)
{
for (int i = cur_seq; i < new_seq; i++)
{
waypoints[i] = waypoints[i+1];
//waypoints[i]->setId(i); // let the local IDs stay the same so that they can be found more easily by the user
}
}
else
{
for (int i = cur_seq; i > new_seq; i--)
{
waypoints[i] = waypoints[i-1];
// waypoints[i]->setId(i);
}
}
waypoints[new_seq] = t;
//waypoints[new_seq]->setId(new_seq);
emit waypointListChanged();
}
}
void UASWaypointManager::localSaveWaypoints(const QString &saveFile)
{
QFile file(saveFile);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
return;
QTextStream out(&file);
for (int i = 0; i < waypoints.size(); i++)
{
waypoints[i]->save(out);
}
file.close();
}
void UASWaypointManager::localLoadWaypoints(const QString &loadFile)
{
QFile file(loadFile);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
return;
while(waypoints.size()>0)
{
Waypoint *t = waypoints[0];
waypoints.remove(0);
delete t;
}
QTextStream in(&file);
while (!in.atEnd())
{
Waypoint *t = new Waypoint();
if(t->load(in))
{
t->setId(waypoints.size());
waypoints.insert(waypoints.size(), t);
}
}
file.close();
emit waypointListChanged();
}
void UASWaypointManager::clearWaypointList()
{
if(current_state == WP_IDLE)
{
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_SETCURRENT;
current_wp_id = seq;
current_state = WP_CLEARLIST;
current_wp_id = 0;
current_partner_systemid = uas.getUASID();
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
sendWaypointSetCurrent(current_wp_id);
sendWaypointClearAll();
}
}
......@@ -266,6 +406,13 @@ void UASWaypointManager::readWaypoints()
{
if(current_state == WP_IDLE)
{
while(waypoints.size()>0)
{
Waypoint *t = waypoints.back();
delete t;
waypoints.pop_back();
}
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
......@@ -300,6 +447,8 @@ void UASWaypointManager::writeWaypoints()
waypoint_buffer.pop_back();
}
bool noCurrent = true;
//copy waypoint data to local buffer
for (int i=0; i < current_count; i++)
{
......@@ -309,17 +458,20 @@ void UASWaypointManager::writeWaypoints()
const Waypoint *cur_s = waypoints.at(i);
cur_d->autocontinue = cur_s->getAutoContinue();
cur_d->current = cur_s->getCurrent();
cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
cur_d->orbit = 0;
cur_d->orbit_direction = 0;
cur_d->param1 = cur_s->getOrbit();
cur_d->param2 = cur_s->getHoldTime();
cur_d->type = 1; //FIXME
cur_d->seq = i;
cur_d->type = 1; //FIXME: we only use local waypoints at the moment
cur_d->seq = i; // don't read out the sequence number of the waypoint class
cur_d->x = cur_s->getX();
cur_d->y = cur_s->getY();
cur_d->z = cur_s->getZ();
cur_d->yaw = cur_s->getYaw();
if (cur_s->getCurrent() && noCurrent)
noCurrent = false;
}
//send the waypoint count to UAS (this starts the send transaction)
......@@ -341,8 +493,7 @@ void UASWaypointManager::sendWaypointClearAll()
wpca.target_system = uas.getUASID();
wpca.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
const QString str = QString("clearing waypoint list...");
emit updateStatusString(str);
emit updateStatusString(QString("clearing waypoint list..."));
mavlink_msg_waypoint_clear_all_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpca);
uas.sendMessage(message);
......@@ -360,8 +511,7 @@ void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
wpsc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpsc.seq = seq;
const QString str = QString("Updating target waypoint...");
emit updateStatusString(str);
emit updateStatusString(QString("Updating target waypoint..."));
mavlink_msg_waypoint_set_current_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpsc);
uas.sendMessage(message);
......@@ -379,8 +529,7 @@ void UASWaypointManager::sendWaypointCount()
wpc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpc.count = current_count;
const QString str = QString("start transmitting waypoints...");
emit updateStatusString(str);
emit updateStatusString(QString("start transmitting waypoints..."));
mavlink_msg_waypoint_count_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpc);
uas.sendMessage(message);
......@@ -397,8 +546,7 @@ void UASWaypointManager::sendWaypointRequestList()
wprl.target_system = uas.getUASID();
wprl.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
const QString str = QString("requesting waypoint list...");
emit updateStatusString(str);
emit updateStatusString(QString("requesting waypoint list..."));
mavlink_msg_waypoint_request_list_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wprl);
uas.sendMessage(message);
......@@ -416,8 +564,7 @@ void UASWaypointManager::sendWaypointRequest(quint16 seq)
wpr.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpr.seq = seq;
const QString str = QString("retrieving waypoint ID %1 of %2 total").arg(wpr.seq).arg(current_count);
emit updateStatusString(str);
emit updateStatusString(QString("retrieving waypoint ID %1 of %2 total").arg(wpr.seq).arg(current_count));
mavlink_msg_waypoint_request_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpr);
uas.sendMessage(message);
......@@ -438,8 +585,7 @@ void UASWaypointManager::sendWaypoint(quint16 seq)
wp->target_system = uas.getUASID();
wp->target_component = MAV_COMP_ID_WAYPOINTPLANNER;
const QString str = QString("sending waypoint ID %1 of %2 total").arg(wp->seq).arg(current_count);
emit updateStatusString(str);
emit updateStatusString(QString("sending waypoint ID %1 of %2 total").arg(wp->seq).arg(current_count));
mavlink_msg_waypoint_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, wp);
uas.sendMessage(message);
......
......@@ -75,7 +75,23 @@ public:
void handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_waypoint_current_t *wpc); ///< Handles received set current waypoint messages
/*@}*/
QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a reference to the local waypoint list. Gives full access to the internal data structure - Subject to change: Public const access and friend access for the waypoint list widget.
/** @name Remote operations */
/*@{*/
void clearWaypointList(); ///< Sends the waypoint clear all message to the MAV
void readWaypoints(); ///< Requests the MAV's current waypoint list
void writeWaypoints(); ///< Sends the local waypoint list to the MAV
int setCurrentWaypoint(quint16 seq); ///< Changes the current waypoint and sends the sequence number of the waypoint that should get the new target waypoint to the UAS
/*@}*/
/** @name Local waypoint list operations */
/*@{*/
const QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a const reference to the local waypoint list.
void localAddWaypoint(Waypoint *wp); ///< locally adds a new waypoint to the end of the list and changes its sequence number accordingly
int localRemoveWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void localMoveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void localSaveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void localLoadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
/*@}*/
private:
/** @name Message send functions */
......@@ -91,15 +107,11 @@ private:
public slots:
void timeout(); ///< Called by the timer if a response times out. Handles send retries.
void setCurrent(quint16 seq); ///< Sends the sequence number of the waypoint that should get the new target waypoint
void clearWaypointList(); ///< Sends the waypoint clear all message to the MAV
void readWaypoints(); ///< Requests the MAV's current waypoint list
void writeWaypoints(); ///< Sends the local waypoint list to the MAV
signals:
void waypointUpdated(quint16,double,double,double,double,bool,bool,double,int); ///< Adds a waypoint to the waypoint list widget
void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string
void waypointListChanged(void); ///< emits signal that the local waypoint list has been changed
void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string
private:
UAS &uas; ///< Reference to the corresponding UAS
......
......@@ -99,7 +99,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
}
else if (dynamic_cast<UDPLink*>(link) != 0)
{
ui.linkGroupBox->setTitle(tr("udp link"));
ui.linkGroupBox->setTitle(tr("UDP Link"));
}
else
{
......
......@@ -633,7 +633,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
{
if (uas)
{
QVector<Waypoint*>& list = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint*>& list = uas->getWaypointManager().getWaypointList();
QColor color;
painter.setBrush(Qt::NoBrush);
......
......@@ -2,9 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL/PIXHAWK PROJECT
<http://www.qgroundcontrol.org>
<http://pixhawk.ethz.ch>
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
......@@ -140,15 +138,18 @@ void MainWindow::buildWidgets()
headDown1 = new HDDisplay(acceptList, this);
headDown2 = new HDDisplay(acceptList2, this);
joystick = new JoystickInput();
dataplot = new QGCDataPlot2D();
}
void MainWindow::connectWidgets(){
void MainWindow::connectWidgets()
{
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), linechart, SLOT(addSystem(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), linechart, SLOT(selectSystem(int)));
connect(mavlink, SIGNAL(receiveLossChanged(int, float)), info, SLOT(updateSendLoss(int, float)));
}
void MainWindow::arrangeCenterStack(){
void MainWindow::arrangeCenterStack()
{
centerStack = new QStackedWidget(this);
......@@ -156,11 +157,13 @@ void MainWindow::arrangeCenterStack(){
centerStack->addWidget(protocol);
centerStack->addWidget(map);
centerStack->addWidget(hud);
centerStack->addWidget(dataplot);
setCentralWidget(centerStack);
}
void MainWindow::configureWindowName(){
void MainWindow::configureWindowName()
{
QList<QHostAddress> hostAddresses = QNetworkInterface::allAddresses();
QString windowname = qApp->applicationName() + " " + qApp->applicationVersion();
bool prevAddr = false;
......@@ -245,11 +248,14 @@ void MainWindow::reloadStylesheet()
{
styleSheet = new QFile(":/images/style-mission.css");
}
if (styleSheet->open(QIODevice::ReadOnly | QIODevice::Text)) {
if (styleSheet->open(QIODevice::ReadOnly | QIODevice::Text))
{
QString style = QString(styleSheet->readAll());
style.replace("ICONDIR", QCoreApplication::applicationDirPath()+ "/images/");
qApp->setStyleSheet(style);
} else {
}
else
{
qDebug() << "Style not set:" << styleSheet->fileName() << "opened: " << styleSheet->isOpen();
}
delete styleSheet;
......@@ -292,12 +298,59 @@ void MainWindow::connectActions()
connect(ui.actionSettingsView, SIGNAL(triggered()), this, SLOT(loadSettingsView()));
connect(ui.actionShow_full_view, SIGNAL(triggered()), this, SLOT(loadAllView()));
connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView()));
connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
// Joystick configuration
connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
}
void MainWindow::showHelp()
{
if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/user_guide")))
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Could not open help in browser");
msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/user_guide in a browser.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
}
}
void MainWindow::showCredits()
{
if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/credits")))
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Could not open credits in browser");
msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/credits in a browser.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
}
}
void MainWindow::showRoadMap()
{
if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/roadmap")))
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Could not open roadmap in browser");
msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/roadmap in a browser.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
}
}
void MainWindow::configure()
{
joystickWidget = new JoystickWidget(joystick, this);
......@@ -485,6 +538,12 @@ void MainWindow::loadPixhawkView()
this->show();
}
void MainWindow::loadDataView()
{
clearView();
centerStack->setCurrentWidget(dataplot);
}
void MainWindow::loadPilotView()
{
clearView();
......
......@@ -62,6 +62,7 @@ This file is part of the PIXHAWK project
#include "HDDisplay.h"
#include "WatchdogControl.h"
#include "HSIDisplay.h"
#include "QGCDataPlot2D.h"
#include "LogCompressor.h"
......@@ -116,6 +117,15 @@ public slots:
void loadAllView();
/** @brief Load MAVLink XML generator view */
void loadMAVLinkView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView();
/** @brief Show the online help for users */
void showHelp();
/** @brief Show the authors / credits */
void showCredits();
/** @brief Show the project roadmap */
void showRoadMap();
// Fixme find a nicer solution that scales to more AP types
void loadSlugsView();
......@@ -158,6 +168,7 @@ protected:
HDDisplay* headDown2;
WatchdogControl* watchdogControl;
HSIDisplay* hsi;
QGCDataPlot2D* dataplot;
// Popup widgets
JoystickWidget* joystickWidget;
......
......@@ -35,7 +35,7 @@
<x>0</x>
<y>0</y>
<width>1000</width>
<height>25</height>
<height>22</height>
</rect>
</property>
<widget class="QMenu" name="menuMGround">
......@@ -75,13 +75,23 @@
<addaction name="actionSettingsView"/>
<addaction name="separator"/>
<addaction name="actionShow_MAVLink_view"/>
<addaction name="actionShow_data_analysis_view"/>
<addaction name="actionShow_full_view"/>
<addaction name="actionStyleConfig"/>
</widget>
<widget class="QMenu" name="menuHelp">
<property name="title">
<string>Help</string>
</property>
<addaction name="actionOnline_documentation"/>
<addaction name="actionProject_Roadmap"/>
<addaction name="actionCredits_Developers"/>
</widget>
<addaction name="menuMGround"/>
<addaction name="menuNetwork"/>
<addaction name="menuUnmanned_System"/>
<addaction name="menuWindow"/>
<addaction name="menuHelp"/>
</widget>
<widget class="QToolBar" name="mainToolBar">
<attribute name="toolBarArea">
......@@ -263,6 +273,42 @@
<string>Show MAVLink view</string>
</property>
</action>
<action name="actionOnline_documentation">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/categories/applications-internet.svg</normaloff>:/images/categories/applications-internet.svg</iconset>
</property>
<property name="text">
<string>Online documentation</string>
</property>
</action>
<action name="actionShow_data_analysis_view">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/apps/utilities-system-monitor.svg</normaloff>:/images/apps/utilities-system-monitor.svg</iconset>
</property>
<property name="text">
<string>Show data analysis view</string>
</property>
</action>
<action name="actionProject_Roadmap">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/software-update-available.svg</normaloff>:/images/status/software-update-available.svg</iconset>
</property>
<property name="text">
<string>Project Roadmap</string>
</property>
</action>
<action name="actionCredits_Developers">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/categories/preferences-system.svg</normaloff>:/images/categories/preferences-system.svg</iconset>
</property>
<property name="text">
<string>Credits / Developers</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
#include <QFileDialog>
#include <QTemporaryFile>
#include <QMessageBox>
#include <QPrintDialog>
#include <QProgressDialog>
#include <QHBoxLayout>
#include <QSvgGenerator>
#include <QPrinter>
#include <QDesktopServices>
#include "QGCDataPlot2D.h"
#include "ui_QGCDataPlot2D.h"
#include "MG.h"
#include <cmath>
#include <QDebug>
QGCDataPlot2D::QGCDataPlot2D(QWidget *parent) :
QWidget(parent),
plot(new IncrementalPlot()),
logFile(NULL),
ui(new Ui::QGCDataPlot2D)
{
ui->setupUi(this);
// Add plot to ui
QHBoxLayout* layout = new QHBoxLayout(ui->plotFrame);
layout->addWidget(plot);
ui->plotFrame->setLayout(layout);
// Connect user actions
connect(ui->selectFileButton, SIGNAL(clicked()), this, SLOT(selectFile()));
connect(ui->saveCsvButton, SIGNAL(clicked()), this, SLOT(saveCsvLog()));
connect(ui->reloadButton, SIGNAL(clicked()), this, SLOT(reloadFile()));
connect(ui->savePlotButton, SIGNAL(clicked()), this, SLOT(savePlot()));
connect(ui->printButton, SIGNAL(clicked()), this, SLOT(print()));
connect(ui->legendCheckBox, SIGNAL(clicked(bool)), plot, SLOT(showLegend(bool)));
connect(ui->style, SIGNAL(currentIndexChanged(QString)), plot, SLOT(setStyleText(QString)));
}
void QGCDataPlot2D::reloadFile()
{
if (QFileInfo(fileName).isReadable())
{
if (ui->inputFileType->currentText().contains("pxIMU"))
{
loadRawLog(fileName, ui->xAxis->currentText(), ui->yAxis->text());
}
else if (ui->inputFileType->currentText().contains("CSV"))
{
loadCsvLog(fileName, ui->xAxis->currentText(), ui->yAxis->text());
}
}
}
void QGCDataPlot2D::loadFile()
{
if (QFileInfo(fileName).isReadable())
{
if (ui->inputFileType->currentText().contains("pxIMU"))
{
loadRawLog(fileName);
}
else if (ui->inputFileType->currentText().contains("CSV"))
{
loadCsvLog(fileName);
}
}
}
void QGCDataPlot2D::savePlot()
{
QString fileName = "plot.svg";
fileName = QFileDialog::getSaveFileName(
this, "Export File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation),
"SVG Documents (*.svg);;");
while(!fileName.endsWith("svg"))
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Unsuitable file extension for SVG");
msgBox.setInformativeText("Please choose .svg as file extension. Click OK to change the file extension, cancel to not save the file.");
msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Ok);
if(msgBox.exec() == QMessageBox::Cancel) break;
fileName = QFileDialog::getSaveFileName(
this, "Export File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation),
"SVG Documents (*.svg);;");
}
exportSVG(fileName);
// else if (fileName.endsWith("pdf"))
// {
// print(fileName);
// }
}
void QGCDataPlot2D::print()
{
QPrinter printer(QPrinter::HighResolution);
// printer.setOutputFormat(QPrinter::PdfFormat);
// //QPrinter printer(QPrinter::HighResolution);
// printer.setOutputFileName(fileName);
QString docName = plot->title().text();
if ( !docName.isEmpty() )
{
docName.replace (QRegExp (QString::fromLatin1 ("\n")), tr (" -- "));
printer.setDocName (docName);
}
printer.setCreator("QGroundControl");
printer.setOrientation(QPrinter::Landscape);
QPrintDialog dialog(&printer);
if ( dialog.exec() )
{
plot->setStyleSheet("QWidget { background-color: #FFFFFF; color: #000000; background-clip: border; font-size: 11pt;}");
plot->setCanvasBackground(Qt::white);
QwtPlotPrintFilter filter;
filter.color(Qt::white, QwtPlotPrintFilter::CanvasBackground);
filter.color(Qt::black, QwtPlotPrintFilter::AxisScale);
filter.color(Qt::black, QwtPlotPrintFilter::AxisTitle);
filter.color(Qt::black, QwtPlotPrintFilter::MajorGrid);
filter.color(Qt::black, QwtPlotPrintFilter::MinorGrid);
if ( printer.colorMode() == QPrinter::GrayScale )
{
int options = QwtPlotPrintFilter::PrintAll;
options &= ~QwtPlotPrintFilter::PrintBackground;
options |= QwtPlotPrintFilter::PrintFrameWithScales;
filter.setOptions(options);
}
plot->print(printer, filter);
}
}
void QGCDataPlot2D::exportSVG(QString fileName)
{
if ( !fileName.isEmpty() )
{
QSvgGenerator generator;
generator.setFileName(fileName);
generator.setSize(QSize(800, 600));
QwtPlotPrintFilter filter;
filter.color(Qt::white, QwtPlotPrintFilter::CanvasBackground);
filter.color(Qt::black, QwtPlotPrintFilter::AxisScale);
filter.color(Qt::black, QwtPlotPrintFilter::AxisTitle);
filter.color(Qt::black, QwtPlotPrintFilter::MajorGrid);
filter.color(Qt::black, QwtPlotPrintFilter::MinorGrid);
plot->print(generator, filter);
}
}
/**
* Selects a filename and attempts immediately to load it.
*/
void QGCDataPlot2D::selectFile()
{
// Let user select the log file name
//QDate date(QDate::currentDate());
// QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), tr("."), tr("Logfile (*.txt)"));
// Store reference to file
QFileInfo fileInfo(fileName);
if (!fileInfo.isReadable())
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Could not open file");
msgBox.setInformativeText(tr("The file is owned by user %1. Is the file currently used by another program?").arg(fileInfo.owner()));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
ui->filenameLabel->setText(tr("Could not open %1").arg(fileInfo.baseName()+"."+fileInfo.completeSuffix()));
}
else
{
ui->filenameLabel->setText(tr("Opened %1").arg(fileInfo.completeBaseName()+"."+fileInfo.completeSuffix()));
// Open and import the file
loadFile();
}
}
void QGCDataPlot2D::loadRawLog(QString file, QString xAxisName, QString yAxisFilter)
{
if (logFile != NULL)
{
logFile->close();
delete logFile;
}
// Postprocess log file
logFile = new QTemporaryFile();
compressor = new LogCompressor(file, logFile->fileName());
// Block UI
QProgressDialog progress("Transforming RAW log file to CSV", "Abort Transformation", 0, 1, this);
progress.setWindowModality(Qt::WindowModal);
while (!compressor->isFinished())
{
MG::SLEEP::usleep(100000);
progress.setMaximum(compressor->getDataLines());
progress.setValue(compressor->getCurrentLine());
}
// Enforce end
progress.setMaximum(compressor->getDataLines());
progress.setValue(compressor->getDataLines());
// Done with preprocessing - now load csv log
loadCsvLog(logFile->fileName(), xAxisName, yAxisFilter);
}
/**
* This function loads a CSV file into the plot. It tries to assign the dimension names
* based on the first data row and tries to guess the separator char.
*
* @param file Name of the file to open
* @param xAxisName Optional paramater. If given, the x axis dimension will be selected to match this string
* @param yAxisFilter Optional parameter. If given, only data dimension names present in the filter string will be
* plotted
*
* @code
*
* QString file = "/home/user/datalog.txt"; // With header: x<tab>y<tab>z
* QString xAxis = "x";
* QString yAxis = "z";
*
* // Plotted result will be x vs z with y ignored.
* @endcode
*/
void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFilter)
{
if (logFile != NULL)
{
logFile->close();
delete logFile;
}
logFile = new QFile(file);
// Load CSV data
if (!logFile->open(QIODevice::ReadOnly | QIODevice::Text))
return;
// Extract header
// Read in values
// Find all keys
QTextStream in(logFile);
// First line is header
QString header = in.readLine();
bool charRead = false;
QString separator = "";
QList<QChar> sepCandidates;
sepCandidates << '\t';
sepCandidates << ',';
sepCandidates << ';';
sepCandidates << ' ';
sepCandidates << '~';
sepCandidates << '|';
// Iterate until separator is found
// or full header is parsed
for (int i = 0; i < header.length(); i++)
{
if (sepCandidates.contains(header.at(i)))
{
// Separator found
if (charRead)
{
separator += header[i];
}
}
else
{
// Char found
charRead = true;
// If the separator is not empty, this char
// has been read after a separator, so detection
// is now complete
if (separator != "") break;
}
}
QString out = separator;
out.replace("\t", "<tab>");
ui->filenameLabel->setText(file.split("/").last().split("\\").last()+" Separator: \""+out+"\"");
//qDebug() << "READING CSV:" << header;
// Clear plot
plot->removeData();
QVector<double> xValues;
QMap<QString, QVector<double>* > yValues;
QStringList curveNames = header.split(separator, QString::SkipEmptyParts);
QString curveName;
// Clear UI elements
ui->xAxis->clear();
ui->yAxis->clear();
int curveNameIndex = 0;
//int xValueIndex = curveNames.indexOf(xAxisName);
QString xAxisFilter;
if (xAxisName == "")
{
xAxisFilter = curveNames.first();
}
else
{
xAxisFilter = xAxisName;
}
foreach(curveName, curveNames)
{
ui->xAxis->addItem(curveName);
if (curveName != xAxisFilter)
{
if ((yAxisFilter == "") || yAxisFilter.contains(curveName))
{
yValues.insert(curveName, new QVector<double>());
// Add separator starting with second item
if (curveNameIndex > 0 && curveNameIndex < curveNames.size())
{
ui->yAxis->setText(ui->yAxis->text()+"|");
}
ui->yAxis->setText(ui->yAxis->text()+curveName);
curveNameIndex++;
}
}
}
// Select current axis in UI
ui->xAxis->setCurrentIndex(curveNames.indexOf(xAxisFilter));
// Read data
double x,y;
while (!in.atEnd())
{
QString line = in.readLine();
QStringList values = line.split(separator, QString::SkipEmptyParts);
foreach(curveName, curveNames)
{
bool okx;
if (curveName == xAxisFilter)
{
// X AXIS HANDLING
// Take this value as x if it is selected
x = values.at(curveNames.indexOf(curveName)).toDouble(&okx);
xValues.append(x - 1270125570000LL);
qDebug() << "x" << x - 1270125570000LL;
}
else
{
// Y AXIS HANDLING
if(yAxisFilter == "" || yAxisFilter.contains(curveName))
{
// Only append y values where a valid x value is present
if (yValues.value(curveName)->size() == xValues.size() - 1)
{
bool oky;
int curveNameIndex = curveNames.indexOf(curveName);
if (values.size() > curveNameIndex)
{
y = values.at(curveNameIndex).toDouble(&oky);
yValues.value(curveName)->append(y);
}
}
}
}
}
}
// Add data array of each curve to the plot at once (fast)
// Iterates through all x-y curve combinations
for (int i = 0; i < yValues.size(); i++)
{
plot->appendData(yValues.keys().at(i), xValues.data(), yValues.values().at(i)->data(), xValues.size());
}
}
/**
* Linear regression (least squares) for n data points.
* Computes:
*
* y = a * x + b
*
* @param x values on x axis
* @param y corresponding values on y axis
* @param n Number of values
* @param a returned slope of line
* @param b y-axis intersection
* @param r regression coefficient. The larger the coefficient is, the better is
* the match of the regression.
* @return 1 on success, 0 on failure (e.g. because of infinite slope)
*/
int QGCDataPlot2D::linearRegression(double* x,double* y,int n,double* a,double* b,double* r)
{
int i;
double sumx=0,sumy=0,sumx2=0,sumy2=0,sumxy=0;
double sxx,syy,sxy;
*a = 0;
*b = 0;
*r = 0;
if (n < 2)
return(FALSE);
/* Conpute some things we need */
for (i=0;i<n;i++) {
sumx += x[i];
sumy += y[i];
sumx2 += (x[i] * x[i]);
sumy2 += (y[i] * y[i]);
sumxy += (x[i] * y[i]);
}
sxx = sumx2 - sumx * sumx / n;
syy = sumy2 - sumy * sumy / n;
sxy = sumxy - sumx * sumy / n;
/* Infinite slope (b), non existant intercept (a) */
if (fabs(sxx) == 0)
return(FALSE);
/* Calculate the slope (b) and intercept (a) */
*b = sxy / sxx;
*a = sumy / n - (*b) * sumx / n;
/* Compute the regression coefficient */
if (fabs(syy) == 0)
*r = 1;
else
*r = sxy / sqrt(sxx * syy);
return(TRUE);
}
void QGCDataPlot2D::saveCsvLog()
{
QString fileName = "export.csv";
fileName = QFileDialog::getSaveFileName(
this, "Export CSV File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation),
"CSV file (*.csv);;Text file (*.txt)");
// QFileInfo fileInfo(fileName);
//
// // Check if we could create a new file in this directory
// QDir dir(fileInfo.absoluteDir());
// QFileInfo dirInfo(dir);
//
// while(!(dirInfo.isWritable()))
// {
// QMessageBox msgBox;
// msgBox.setIcon(QMessageBox::Critical);
// msgBox.setText("File cannot be written, Operating System denies permission");
// msgBox.setInformativeText("Please choose a different file name or directory. Click OK to change the file, cancel to not save the file.");
// msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);
// msgBox.setDefaultButton(QMessageBox::Ok);
// if(msgBox.exec() == QMessageBox::Cancel) break;
// fileName = QFileDialog::getSaveFileName(
// this, "Export CSV File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation),
// "CSV file (*.csv);;Text file (*.txt)");
// }
bool success = logFile->copy(fileName);
qDebug() << "Saved CSV log. Success: " << success;
//qDebug() << "READE TO SAVE CSV LOG TO " << fileName;
}
QGCDataPlot2D::~QGCDataPlot2D()
{
delete ui;
}
void QGCDataPlot2D::changeEvent(QEvent *e)
{
QWidget::changeEvent(e);
switch (e->type()) {
case QEvent::LanguageChange:
ui->retranslateUi(this);
break;
default:
break;
}
}
#ifndef QGCDATAPLOT2D_H
#define QGCDATAPLOT2D_H
#include <QWidget>
#include <QFile>
#include "IncrementalPlot.h"
#include "LogCompressor.h"
namespace Ui {
class QGCDataPlot2D;
}
class QGCDataPlot2D : public QWidget {
Q_OBJECT
public:
QGCDataPlot2D(QWidget *parent = 0);
~QGCDataPlot2D();
/** @brief Linear regression over data points */
int linearRegression(double *x,double *y,int n,double *a,double *b,double *r);
public slots:
void loadFile();
/** @brief Reload a file, with filtering enabled */
void reloadFile();
void selectFile();
void loadCsvLog(QString file, QString xAxisName="", QString yAxisFilter="");
void loadRawLog(QString file, QString xAxisName="", QString yAxisFilter="");
void saveCsvLog();
/** @brief Save plot to PDF or SVG */
void savePlot();
/** @brief Export SVG file */
void exportSVG(QString file);
/** @brief Print or save PDF file (MacOS/Linux) */
void print();
protected:
void changeEvent(QEvent *e);
IncrementalPlot* plot;
LogCompressor* compressor;
QFile* logFile;
QString fileName;
private:
Ui::QGCDataPlot2D *ui;
};
#endif // QGCDATAPLOT2D_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCDataPlot2D</class>
<widget class="QWidget" name="QGCDataPlot2D">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>807</width>
<height>308</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="2,10,2,0,0,0,0,0,0,0,0,0,0">
<item row="0" column="0" colspan="2">
<widget class="QLabel" name="label_2">
<property name="text">
<string>X</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QComboBox" name="xAxis"/>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Y</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLineEdit" name="yAxis"/>
</item>
<item row="0" column="5" colspan="2">
<widget class="QComboBox" name="style">
<item>
<property name="text">
<string>Style..</string>
</property>
</item>
<item>
<property name="text">
<string>Only crosses</string>
</property>
</item>
<item>
<property name="text">
<string>Only circles</string>
</property>
</item>
<item>
<property name="text">
<string>Only dots</string>
</property>
</item>
<item>
<property name="text">
<string>Lines and crosses</string>
</property>
</item>
<item>
<property name="text">
<string>Lines and circles</string>
</property>
</item>
<item>
<property name="text">
<string>Lines and dots</string>
</property>
</item>
<item>
<property name="text">
<string>Dotted lines and crosses</string>
</property>
</item>
<item>
<property name="text">
<string>Dotted lines and circles</string>
</property>
</item>
<item>
<property name="text">
<string>Dotted lines and dots</string>
</property>
</item>
<item>
<property name="text">
<string>Dashed lines and crosses</string>
</property>
</item>
<item>
<property name="text">
<string>Dashed lines and circles</string>
</property>
</item>
<item>
<property name="text">
<string>Dashed lines and dots</string>
</property>
</item>
</widget>
</item>
<item row="0" column="9">
<widget class="QPushButton" name="reloadButton">
<property name="text">
<string>Reload</string>
</property>
</widget>
</item>
<item row="0" column="10">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="11">
<widget class="QPushButton" name="savePlotButton">
<property name="text">
<string>Save Plot</string>
</property>
</widget>
</item>
<item row="1" column="0" colspan="13">
<widget class="QFrame" name="plotFrame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>File</string>
</property>
</widget>
</item>
<item row="2" column="1" colspan="2">
<widget class="QComboBox" name="inputFileType">
<item>
<property name="text">
<string>CSV</string>
</property>
</item>
<item>
<property name="text">
<string>pxIMU</string>
</property>
</item>
<item>
<property name="text">
<string>RAW</string>
</property>
</item>
</widget>
</item>
<item row="2" column="3" colspan="4">
<widget class="QLabel" name="filenameLabel">
<property name="text">
<string>Please select input file..</string>
</property>
</widget>
</item>
<item row="2" column="10">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="12">
<widget class="QPushButton" name="printButton">
<property name="text">
<string>Print</string>
</property>
</widget>
</item>
<item row="2" column="12">
<widget class="QPushButton" name="saveCsvButton">
<property name="text">
<string>Save CSV</string>
</property>
</widget>
</item>
<item row="2" column="9">
<widget class="QPushButton" name="selectFileButton">
<property name="text">
<string>Select file</string>
</property>
</widget>
</item>
<item row="0" column="7">
<widget class="QCheckBox" name="symmetricCheckBox">
<property name="text">
<string>Symmetric</string>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QCheckBox" name="legendCheckBox">
<property name="text">
<string>Legend</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<author/>
<comment/>
<exportmacro/>
<class>QGCFirmwareUpdate</class>
<widget class="QWidget" name="QGCFirmwareUpdate">
<property name="geometry">
......@@ -16,6 +14,6 @@
<string>Form</string>
</property>
</widget>
<pixmapfunction/>
<resources/>
<connections/>
</ui>
......@@ -165,7 +165,7 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
{
Q_UNUSED(uas);
// Reference to item in tree
QTreeWidgetItem* parameterItem;
QTreeWidgetItem* parameterItem = NULL;
// Get component
if (!components->contains(component))
......@@ -405,7 +405,7 @@ void QGCParamWidget::loadParameters()
changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), (float)wpParams.at(3).toDouble());
qDebug() << "MARKING COMP" << wpParams.at(1).toInt() << "PARAM" << wpParams.at(2) << "VALUE" << (float)wpParams.at(3).toDouble() << "AS CHANGED";
//qDebug() << "MARKING COMP" << wpParams.at(1).toInt() << "PARAM" << wpParams.at(2) << "VALUE" << (float)wpParams.at(3).toDouble() << "AS CHANGED";
// Mark in UI
......
......@@ -55,8 +55,6 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
listLayout->setAlignment(Qt::AlignTop);
m_ui->listWidget->setLayout(listLayout);
wpViews = QMap<Waypoint*, WaypointView*>();
this->uas = NULL;
// ADD WAYPOINT
......@@ -93,11 +91,6 @@ WaypointList::~WaypointList()
delete m_ui;
}
void WaypointList::updateStatusLabel(const QString &string)
{
m_ui->statusLabel->setText(string);
}
void WaypointList::updateLocalPosition(UASInterface* uas, double x, double y, double z, quint64 usec)
{
Q_UNUSED(uas);
......@@ -122,90 +115,38 @@ void WaypointList::setUAS(UASInterface* uas)
{
this->uas = uas;
connect(&uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(&uas->getWaypointManager(), SIGNAL(waypointUpdated(quint16,double,double,double,double,bool,bool,double,int)), this, SLOT(setWaypoint(quint16,double,double,double,double,bool,bool,double,int)));
connect(&uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(this, SIGNAL(sendWaypoints()), &uas->getWaypointManager(), SLOT(writeWaypoints()));
connect(this, SIGNAL(requestWaypoints()), &uas->getWaypointManager(), SLOT(readWaypoints()));
connect(this, SIGNAL(clearWaypointList()), &uas->getWaypointManager(), SLOT(clearWaypointList()));
connect(this, SIGNAL(setCurrent(quint16)), &uas->getWaypointManager(), SLOT(setCurrent(quint16)));
connect(&uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(&uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void)));
connect(&uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
}
}
void WaypointList::setWaypoint(quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current, double orbit, int holdTime)
{
if (this->uas)
{
Waypoint* wp = new Waypoint(id, x, y, z, yaw, autocontinue, current, orbit, holdTime);
addWaypoint(wp);
}
}
void WaypointList::waypointReached(quint16 waypointId)
void WaypointList::saveWaypoints()
{
if (this->uas)
if (uas)
{
updateStatusLabel(QString("Waypoint %1 reached.").arg(waypointId));
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./waypoints.txt", tr("Waypoint File (*.txt)"));
uas->getWaypointManager().localSaveWaypoints(fileName);
}
}
void WaypointList::changeCurrentWaypoint(quint16 seq)
void WaypointList::loadWaypoints()
{
if (this->uas)
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
waypoints[i]->setCurrent(true);
widget->setCurrent(true);
emit setCurrent(seq);
}
else
{
waypoints[i]->setCurrent(false);
widget->setCurrent(false);
}
}
redrawList();
}
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
uas->getWaypointManager().localLoadWaypoints(fileName);
}
}
void WaypointList::currentWaypointChanged(quint16 seq)
void WaypointList::transmit()
{
if (this->uas)
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
waypoints[i]->setCurrent(true);
widget->setCurrent(true);
}
else
{
waypoints[i]->setCurrent(false);
widget->setCurrent(false);
}
}
redrawList();
}
uas->getWaypointManager().writeWaypoints();
}
}
......@@ -213,38 +154,25 @@ void WaypointList::read()
{
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(waypoints.size()>0)
{
removeWaypoint(waypoints[0]);
}
emit requestWaypoints();
uas->getWaypointManager().readWaypoints();
}
}
void WaypointList::transmit()
{
emit sendWaypoints();
//emit requestWaypoints(); FIXME
}
void WaypointList::add()
{
// Only add waypoints if UAS is present
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
addWaypoint(new Waypoint(waypoints.size(), last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime()));
Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
}
else
{
addWaypoint(new Waypoint(waypoints.size(), 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000));
Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
}
}
......@@ -253,47 +181,66 @@ void WaypointList::addCurrentPositonWaypoint()
{
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
addWaypoint(new Waypoint(waypoints.size(), (float)(qRound(mavX*100))/100.f, (float)(qRound(mavY*100))/100.f, (float)(qRound(mavZ*100))/100.f, (float)(qRound(mavYaw*100))/100.f, last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime()));
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
}
else
{
addWaypoint(new Waypoint(waypoints.size(), (float)(qRound(mavX*100))/100.f, (float)(qRound(mavY*100))/100.f, (float)(qRound(mavZ*100))/100.f, (float)(qRound(mavYaw*100))/100.f, true, true, 0.15, 2000));
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
}
}
void WaypointList::updateStatusLabel(const QString &string)
{
m_ui->statusLabel->setText(string);
}
void WaypointList::changeCurrentWaypoint(quint16 seq)
{
if (uas)
{
uas->getWaypointManager().setCurrentWaypoint(seq);
}
}
void WaypointList::addWaypoint(Waypoint* wp)
void WaypointList::currentWaypointChanged(quint16 seq)
{
if (uas)
{
uas->getWaypointManager().getWaypointList().push_back(wp);
if (!wpViews.contains(wp))
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (seq < waypoints.size())
{
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
listLayout->addWidget(wpViews.value(wp));
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
for(int i = 0; i < waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
widget->setCurrent(true);
}
else
{
widget->setCurrent(false);
}
}
}
}
}
void WaypointList::redrawList()
void WaypointList::waypointListChanged()
{
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
// Clear list layout
// first remove all views of non existing waypoints
if (!wpViews.empty())
{
QMapIterator<Waypoint*,WaypointView*> viewIt(wpViews);
......@@ -301,13 +248,43 @@ void WaypointList::redrawList()
while(viewIt.hasNext())
{
viewIt.next();
listLayout->removeWidget(viewIt.value());
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == cur)
{
break;
}
}
if (i == waypoints.size())
{
WaypointView* widget = wpViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
}
}
// Re-add waypoints
for(int i = 0; i < waypoints.size(); i++)
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp))
{
listLayout->addWidget(wpViews.value(waypoints[i]));
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
}
}
}
......@@ -316,27 +293,20 @@ void WaypointList::moveUp(Waypoint* wp)
{
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
int id = wp->getId();
if (waypoints.size() > 1 && waypoints.size() > id)
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++)
{
Waypoint* temp = waypoints[id];
if (id > 0)
{
waypoints[id] = waypoints[id-1];
waypoints[id-1] = temp;
waypoints[id-1]->setId(id-1);
waypoints[id]->setId(id);
}
else
{
waypoints[id] = waypoints[waypoints.size()-1];
waypoints[waypoints.size()-1] = temp;
waypoints[waypoints.size()-1]->setId(waypoints.size()-1);
waypoints[id]->setId(id);
}
redrawList();
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the first entry, move it
if (i < waypoints.size() && i > 0)
{
uas->getWaypointManager().localMoveWaypoint(i, i-1);
}
}
}
......@@ -345,27 +315,20 @@ void WaypointList::moveDown(Waypoint* wp)
{
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
int id = wp->getId();
if (waypoints.size() > 1 && waypoints.size() > id)
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++)
{
Waypoint* temp = waypoints[id];
if (id != waypoints.size()-1)
{
waypoints[id] = waypoints[id+1];
waypoints[id+1] = temp;
waypoints[id+1]->setId(id+1);
waypoints[id]->setId(id);
}
else
{
waypoints[id] = waypoints[0];
waypoints[0] = temp;
waypoints[0]->setId(0);
waypoints[id]->setId(id);
}
redrawList();
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the last entry, move it
if (i < waypoints.size()-1)
{
uas->getWaypointManager().localMoveWaypoint(i, i+1);
}
}
}
......@@ -374,24 +337,7 @@ void WaypointList::removeWaypoint(Waypoint* wp)
{
if (uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
// Delete from list
if (wp != NULL)
{
waypoints.remove(wp->getId());
for(int i = wp->getId(); i < waypoints.size(); i++)
{
waypoints[i]->setId(i);
}
// Remove from view
WaypointView* widget = wpViews.find(wp).value();
wpViews.remove(wp);
widget->hide();
listLayout->removeWidget(widget);
delete wp;
}
uas->getWaypointManager().localRemoveWaypoint(wp->getId());
}
}
......@@ -406,52 +352,3 @@ void WaypointList::changeEvent(QEvent *e)
}
}
void WaypointList::saveWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./waypoints.txt", tr("Waypoint File (*.txt)"));
QFile file(fileName);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
return;
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
QTextStream in(&file);
for (int i = 0; i < waypoints.size(); i++)
{
Waypoint* wp = waypoints[i];
in << "\t" << wp->getId() << "\t" << wp->getX() << "\t" << wp->getY() << "\t" << wp->getZ() << "\t" << wp->getYaw() << "\t" << wp->getAutoContinue() << "\t" << wp->getCurrent() << "\t" << wp->getOrbit() << "\t" << wp->getHoldTime() << "\n";
in.flush();
}
file.close();
}
}
void WaypointList::loadWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
QFile file(fileName);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
return;
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(waypoints.size()>0)
{
removeWaypoint(waypoints[0]);
}
QTextStream in(&file);
while (!in.atEnd())
{
QStringList wpParams = in.readLine().split("\t");
if (wpParams.size() == 10)
addWaypoint(new Waypoint(wpParams[1].toInt(), wpParams[2].toDouble(), wpParams[3].toDouble(), wpParams[4].toDouble(), wpParams[5].toDouble(), (wpParams[6].toInt() == 1 ? true : false), (wpParams[7].toInt() == 1 ? true : false), wpParams[8].toDouble(), wpParams[9].toInt()));
}
file.close();
}
}
......@@ -54,42 +54,44 @@ class WaypointList : public QWidget {
virtual ~WaypointList();
public slots:
void updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec);
void updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
void setUAS(UASInterface* uas);
void redrawList();
//UI Buttons
//Waypoint list operations
/** @brief Save the local waypoint list to a file */
void saveWaypoints();
/** @brief Load a waypoint list from a file */
void loadWaypoints();
/** @brief Transmit the local waypoint list to the UAS */
void transmit();
/** @brief Read the remote waypoint list */
void read();
/** @brief Add a waypoint */
void add();
/** @brief Add a waypoint at the current MAV position */
void addCurrentPositonWaypoint();
void moveUp(Waypoint* wp);
void moveDown(Waypoint* wp);
//Update events
/** @brief sets statusLabel string */
void updateStatusLabel(const QString &string);
void changeCurrentWaypoint(quint16 seq); ///< The user wants to change the current waypoint
void currentWaypointChanged(quint16 seq); ///< The waypointplanner changed the current waypoint
void setWaypoint(quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current, double orbit, int holdTime);
void addWaypoint(Waypoint* wp);
/** @brief The user wants to change the current waypoint */
void changeCurrentWaypoint(quint16 seq);
/** @brief The waypoint planner changed the current waypoint */
void currentWaypointChanged(quint16 seq);
/** @brief The waypoint manager informs that the waypoint list was changed */
void waypointListChanged(void);
// Waypoint operations
void moveUp(Waypoint* wp);
void moveDown(Waypoint* wp);
void removeWaypoint(Waypoint* wp);
void waypointReached(quint16 waypointId);
void updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec);
void updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
signals:
void sendWaypoints();
void requestWaypoints();
void clearWaypointList();
void setCurrent(quint16);
protected:
virtual void changeEvent(QEvent *e);
protected:
QMap<Waypoint*, WaypointView*> wpViews;
QVBoxLayout* listLayout;
UASInterface* uas;
......
......@@ -48,15 +48,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
this->wp = wp;
// Read values and set user interface
m_ui->xSpinBox->setValue(wp->getX());
m_ui->ySpinBox->setValue(wp->getY());
m_ui->zSpinBox->setValue(wp->getZ());
m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.);
m_ui->selectedBox->setChecked(wp->getCurrent());
m_ui->autoContinue->setChecked(wp->getAutoContinue());
m_ui->idLabel->setText(QString("%1").arg(wp->getId()));\
m_ui->orbitSpinBox->setValue(wp->getOrbit());
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
updateValues();
connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
......@@ -110,15 +102,30 @@ void WaypointView::changedCurrent(int state)
{
if (state == 0)
{
wp->setCurrent(false);
//m_ui->selectedBox->setChecked(true);
//m_ui->selectedBox->setCheckState(Qt::Checked);
//wp->setCurrent(false);
}
else
{
wp->setCurrent(true);
//wp->setCurrent(true);
emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
}
}
void WaypointView::updateValues()
{
m_ui->xSpinBox->setValue(wp->getX());
m_ui->ySpinBox->setValue(wp->getY());
m_ui->zSpinBox->setValue(wp->getZ());
m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.);
m_ui->selectedBox->setChecked(wp->getCurrent());
m_ui->autoContinue->setChecked(wp->getAutoContinue());
m_ui->idLabel->setText(QString("%1").arg(wp->getId()));\
m_ui->orbitSpinBox->setValue(wp->getOrbit());
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
}
void WaypointView::setCurrent(bool state)
{
if (state)
......
......@@ -57,6 +57,7 @@ public slots:
void remove();
void changedAutoContinue(int);
void changedCurrent(int);
void updateValues(void);
void setYaw(int); //hidden degree to radian conversion
......
#include <qwt_plot.h>
#include <qwt_plot_canvas.h>
#include <qwt_plot_curve.h>
#include <qwt_symbol.h>
#include <qwt_plot_layout.h>
#include <qwt_plot_grid.h>
#include <qwt_scale_engine.h>
#include "IncrementalPlot.h"
#include <Scrollbar.h>
#include <ScrollZoomer.h>
#include <float.h>
#if QT_VERSION >= 0x040000
#include <qpaintengine.h>
#endif
CurveData::CurveData():
d_count(0)
{
}
void CurveData::append(double *x, double *y, int count)
{
int newSize = ( (d_count + count) / 1000 + 1 ) * 1000;
if ( newSize > size() )
{
d_x.resize(newSize);
d_y.resize(newSize);
}
for ( register int i = 0; i < count; i++ )
{
d_x[d_count + i] = x[i];
d_y[d_count + i] = y[i];
}
d_count += count;
}
int CurveData::count() const
{
return d_count;
}
int CurveData::size() const
{
return d_x.size();
}
const double *CurveData::x() const
{
return d_x.data();
}
const double *CurveData::y() const
{
return d_y.data();
}
IncrementalPlot::IncrementalPlot(QWidget *parent):
QwtPlot(parent)
{
setAutoReplot(false);
setFrameStyle(QFrame::NoFrame);
setLineWidth(0);
setStyleText("solid crosses");
setCanvasLineWidth(2);
plotLayout()->setAlignCanvasToScales(true);
QwtPlotGrid *grid = new QwtPlotGrid;
grid->setMajPen(QPen(Qt::gray, 0, Qt::DotLine));
grid->attach(this);
QwtLinearScaleEngine* yScaleEngine = new QwtLinearScaleEngine();
setAxisScaleEngine(QwtPlot::yLeft, yScaleEngine);
setAxisAutoScale(xBottom);
setAxisAutoScale(yLeft);
resetScaling();
// enable zooming
zoomer = new ScrollZoomer(canvas());
zoomer->setRubberBandPen(QPen(Qt::red, 2, Qt::DotLine));
zoomer->setTrackerPen(QPen(Qt::red));
//zoomer->setZoomBase(QwtDoubleRect());
legend = NULL;
colors = QList<QColor>();
nextColor = 0;
///> Color map for plots, includes 20 colors
///> Map will start from beginning when the first 20 colors are exceeded
colors.append(QColor(242,255,128));
colors.append(QColor(70,80,242));
colors.append(QColor(232,33,47));
colors.append(QColor(116,251,110));
colors.append(QColor(81,183,244));
colors.append(QColor(234,38,107));
colors.append(QColor(92,247,217));
colors.append(QColor(151,59,239));
colors.append(QColor(231,72,28));
colors.append(QColor(236,48,221));
colors.append(QColor(75,133,243));
colors.append(QColor(203,254,121));
colors.append(QColor(104,64,240));
colors.append(QColor(200,54,238));
colors.append(QColor(104,250,138));
colors.append(QColor(235,43,165));
colors.append(QColor(98,248,176));
colors.append(QColor(161,252,116));
colors.append(QColor(87,231,246));
colors.append(QColor(230,126,23));
}
IncrementalPlot::~IncrementalPlot()
{
}
void IncrementalPlot::showLegend(bool show)
{
if (show)
{
if (legend == NULL)
{
legend = new QwtLegend;
legend->setFrameStyle(QFrame::Box);
}
insertLegend(legend, QwtPlot::RightLegend);
}
else
{
delete legend;
legend = NULL;
}
replot();
}
/**
* Set datapoint and line style. This interface is intented
* to be directly connected to the UI and allows to parse
* human-readable, textual descriptions into plot specs.
*
* Data points: Either "circles", "crosses" or the default "dots"
* Lines: Either "dotted", ("solid"/"line") or no lines if not used
*
* No special formatting is needed, as long as the keywords are contained
* in the string. Lower/uppercase is ignored as well.
*
* @param style Formatting string for line/data point style
*/
void IncrementalPlot::setStyleText(QString style)
{
foreach (QwtPlotCurve* curve, d_curve)
{
// Style of datapoints
if (style.toLower().contains("circles"))
{
curve->setSymbol(QwtSymbol(QwtSymbol::Ellipse,
QBrush(curve->pen().color()), curve->pen(), QSize(5, 5)) );
}
else if (style.toLower().contains("crosses"))
{
curve->setSymbol(QwtSymbol(QwtSymbol::XCross,
QBrush(curve->pen().color()), curve->pen(), QSize(5, 5)) );
}
else // Always show dots (style.toLower().contains("dots"))
{
curve->setSymbol(QwtSymbol(QwtSymbol::Rect,
QBrush(curve->pen().color()), curve->pen(), QSize(1, 1)) );
}
// Style of lines
if (style.toLower().contains("dotted"))
{
curve->setStyle(QwtPlotCurve::Dots);
}
else if (style.toLower().contains("line") || style.toLower().contains("solid"))
{
curve->setStyle(QwtPlotCurve::Lines);
}
else
{
curve->setStyle(QwtPlotCurve::NoCurve);
}
}
}
void IncrementalPlot::resetScaling()
{
xmin = 0;
xmax = 500;
ymin = 0;
ymax = 500;
setAxisScale(xBottom, xmin+xmin*0.05, xmax+xmax*0.05);
setAxisScale(yLeft, ymin+ymin*0.05, ymax+ymax*0.05);
replot();
// Make sure the first data access hits these
xmin = DBL_MAX;
xmax = DBL_MIN;
ymin = DBL_MAX;
ymax = DBL_MIN;
}
void IncrementalPlot::appendData(QString key, double x, double y)
{
appendData(key, &x, &y, 1);
}
void IncrementalPlot::appendData(QString key, double *x, double *y, int size)
{
CurveData* data;
QwtPlotCurve* curve;
if (!d_data.contains(key))
{
data = new CurveData;
d_data.insert(key, data);
}
else
{
data = d_data.value(key);
}
if (!d_curve.contains(key))
{
curve = new QwtPlotCurve(key);
d_curve.insert(key, curve);
curve->setStyle(QwtPlotCurve::NoCurve);
curve->setPaintAttribute(QwtPlotCurve::PaintFiltered);
const QColor &c = getNextColor();
curve->setSymbol(QwtSymbol(QwtSymbol::XCross,
QBrush(c), QPen(c), QSize(5, 5)) );
curve->attach(this);
}
else
{
curve = d_curve.value(key);
}
data->append(x, y, size);
curve->setRawData(data->x(), data->y(), data->count());
bool scaleChanged = false;
// Update scales
for (int i = 0; i<size; i++)
{
if (x[i] < xmin)
{
xmin = x[i];
scaleChanged = true;
}
if (x[i] > xmax)
{
xmax = x[i];
scaleChanged = true;
}
if (y[i] < ymin)
{
ymin = y[i];
scaleChanged = true;
}
if (y[i] > ymax)
{
ymax = y[i];
scaleChanged = true;
}
}
// setAxisScale(xBottom, xmin+xmin*0.05, xmax+xmax*0.05);
// setAxisScale(yLeft, ymin+ymin*0.05, ymax+ymax*0.05);
//#ifdef __GNUC__
//#warning better use QwtData
//#endif
//replot();
if(scaleChanged)
{
setAxisScale(xBottom, xmin+xmin*0.05, xmax+xmax*0.05);
setAxisScale(yLeft, ymin+ymin*0.05, ymax+ymax*0.05);
zoomer->setZoomBase(true);
}
else
{
const bool cacheMode =
canvas()->testPaintAttribute(QwtPlotCanvas::PaintCached);
#if QT_VERSION >= 0x040000 && defined(Q_WS_X11)
// Even if not recommended by TrollTech, Qt::WA_PaintOutsidePaintEvent
// works on X11. This has an tremendous effect on the performance..
canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, true);
#endif
canvas()->setPaintAttribute(QwtPlotCanvas::PaintCached, false);
// FIXME Check if here all curves should be drawn
// QwtPlotCurve* plotCurve;
// foreach(plotCurve, d_curve)
// {
// plotCurve->draw(0, curve->dataSize()-1);
// }
curve->draw(curve->dataSize() - size, curve->dataSize() - 1);
canvas()->setPaintAttribute(QwtPlotCanvas::PaintCached, cacheMode);
#if QT_VERSION >= 0x040000 && defined(Q_WS_X11)
canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, false);
#endif
}
}
QList<QColor> IncrementalPlot::getColorMap()
{
return colors;
}
QColor IncrementalPlot::getNextColor()
{
/* Return current color and increment counter for next round */
nextColor++;
if(nextColor >= colors.size()) nextColor = 0;
return colors[nextColor++];
}
QColor IncrementalPlot::getColorForCurve(QString id)
{
return d_curve.value(id)->pen().color();
}
void IncrementalPlot::removeData()
{
foreach (QwtPlotCurve* curve, d_curve)
{
delete curve;
}
d_curve.clear();
foreach (CurveData* data, d_data)
{
delete data;
}
d_data.clear();
resetScaling();
replot();
}
#ifndef INCREMENTALPLOT_H
#define INCREMENTALPLOT_H
#include <QTimer>
#include <qwt_array.h>
#include <qwt_plot.h>
#include <qwt_legend.h>
#include <QMap>
#include "ScrollZoomer.h"
class QwtPlotCurve;
class CurveData
{
// A container class for growing data
public:
CurveData();
void append(double *x, double *y, int count);
int count() const;
int size() const;
const double *x() const;
const double *y() const;
private:
int d_count;
QwtArray<double> d_x;
QwtArray<double> d_y;
QTimer *d_timer;
int d_timerCount;
};
class IncrementalPlot : public QwtPlot
{
Q_OBJECT
public:
IncrementalPlot(QWidget *parent = NULL);
virtual ~IncrementalPlot();
/** @brief Get color map of this plot */
QList<QColor> getColorMap();
/** @brief Get next color of color map */
QColor getNextColor();
/** @brief Get color for curve id */
QColor getColorForCurve(QString id);
public slots:
void appendData(QString key, double x, double y);
void appendData(QString key, double *x, double *y, int size);
void resetScaling();
void removeData();
/** @brief Show the plot legend */
void showLegend(bool show);
/** @brief Set new plot style */
void setStyleText(QString style);
protected:
QList<QColor> colors;
int nextColor;
ScrollZoomer* zoomer;
QwtLegend* legend;
double xmin;
double xmax;
double ymin;
double ymax;
private:
QMap<QString, CurveData* > d_data;
QMap<QString, QwtPlotCurve* > d_curve;
};
#endif /* INCREMENTALPLOT_H */
......@@ -134,7 +134,8 @@ d_curve(NULL)
setCanvasBackground(QColor(40, 40, 40));
// Enable zooming
Zoomer *zoomer = new Zoomer(canvas());
//zoomer = new Zoomer(canvas());
zoomer = new ScrollZoomer(canvas());
zoomer->setRubberBandPen(QPen(Qt::blue, 2, Qt::DotLine));
zoomer->setTrackerPen(QPen(Qt::blue));
......@@ -581,16 +582,23 @@ void LinechartPlot::paintRealtime()
{
// Update plot window value to new max time if the last time was also the max time
windowLock.lock();
if (automaticScrollActive) {
if (MG::TIME::getGroundTimeNow() > maxTime && abs(MG::TIME::getGroundTimeNow() - maxTime) < 5000000)
{
plotPosition = MG::TIME::getGroundTimeNow();
}
else
{
if (automaticScrollActive)
{
// FIXME Check, but commenting this out should have been
// beneficial (does only add complexity)
// if (MG::TIME::getGroundTimeNow() > maxTime && abs(MG::TIME::getGroundTimeNow() - maxTime) < 5000000)
// {
// plotPosition = MG::TIME::getGroundTimeNow();
// }
// else
// {
plotPosition = maxTime;// + lastMaxTimeAdded.msec();
}
// }
setAxisScale(QwtPlot::xBottom, plotPosition - plotInterval, plotPosition, timeScaleStep);
// FIXME Last fix for scroll zoomer is here
//setAxisScale(QwtPlot::yLeft, minValue + minValue * 0.05, maxValue + maxValue * 0.05f, (maxValue - minValue) / 10.0);
/* Notify about change. Even if the window position was not changed
* itself, the relative position of the window to the interval must
* have changed, as the interval likely increased in length */
......@@ -618,8 +626,17 @@ void LinechartPlot::paintRealtime()
canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, directPaint);
#endif
// Only set current view as zoombase if zoomer is not active
// else we could not zoom out any more
replot();
if(zoomer->zoomStack().size() < 2)
{
zoomer->setZoomBase(true);
}
else
{
replot();
}
#ifndef _WIN32
canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, oldDirectPaint);
......@@ -726,10 +743,11 @@ void TimeSeriesData::append(quint64 ms, double value)
{
dataMutex.lock();
// Pre- allocate new space
// FIXME Check this for validity
if(static_cast<quint64>(size()) < (count + 100))
{
this->ms.resize(size() + 1000);
this->value.resize(size() + 1000);
this->ms.resize(size() + 10000);
this->value.resize(size() + 10000);
}
this->ms[count] = ms;
this->value[count] = value;
......@@ -779,16 +797,16 @@ void TimeSeriesData::append(quint64 ms, double value)
if(maxInterval > 0)
{ // maxInterval = 0 means infinite
if(interval >= maxInterval && !this->ms.isEmpty() && !this->value.isEmpty())
if(interval > maxInterval && !this->ms.isEmpty() && !this->value.isEmpty())
{
// The time at which this time series should be cut
quint64 minTime = stopTime - maxInterval;
double minTime = stopTime - maxInterval;
// Delete elements from the start of the list as long the time
// value of this elements is before the cut time
while(this->ms.first() < minTime)
{
this->ms.remove(0);
this->value.remove(0);
this->ms.pop_front();
this->value.pop_front();
}
}
}
......
......@@ -265,6 +265,7 @@ protected:
QMap<QString, QwtPlotCurve*> curves;
QMap<QString, TimeSeriesData*> data;
QMap<QString, QwtScaleMap*> scaleMaps;
ScrollZoomer* zoomer;
QList<QColor> colors;
int nextColor;
......
......@@ -42,6 +42,8 @@ This file is part of the PIXHAWK project
#include <QColor>
#include <QPalette>
#include <QFileDialog>
#include <QDesktopServices>
#include <QMessageBox>
#include "LinechartWidget.h"
#include "LinechartPlot.h"
......@@ -259,20 +261,39 @@ void LinechartWidget::startLogging()
// Let user select the log file name
QDate date(QDate::currentDate());
// QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), tr("."), tr("Logfile (*.txt)"));
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.txt, *.csv);;"));
// Store reference to file
logFile = new QFile(fileName);
if (logFile->open(QIODevice::WriteOnly | QIODevice::Text))
// Append correct file ending if needed
bool abort = false;
while (!(fileName.endsWith(".txt") || fileName.endsWith(".csv")))
{
logging = true;
logindex++;
logButton->setText(tr("Stop logging"));
disconnect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
connect(logButton, SIGNAL(clicked()), this, SLOT(stopLogging()));
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Unsuitable file extension for logfile");
msgBox.setInformativeText("Please choose .txt or .csv as file extension. Click OK to change the file extension, cancel to not start logging.");
msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Ok);
if(msgBox.exec() == QMessageBox::Cancel)
{
abort = true;
break;
}
fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.txt, *.csv);;"));
}
else
// Check if the user did not abort the file save dialog
if (!abort && fileName != "")
{
return;
logFile = new QFile(fileName);
if (logFile->open(QIODevice::WriteOnly | QIODevice::Text))
{
logging = true;
logindex++;
logButton->setText(tr("Stop logging"));
disconnect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
connect(logButton, SIGNAL(clicked()), this, SLOT(stopLogging()));
}
}
}
......@@ -418,7 +439,7 @@ void LinechartWidget::removeCurve(QString curve)
Q_UNUSED(curve)
//TODO @todo Ensure that the button for a curve gets deleted when the original curve is deleted
// Remove name
}
}
void LinechartWidget::setActive(bool active)
{
......
x y z
0 1 2
1 2 3
2 3 4
3 4 5
4 5 6
5 10 15
6 11 16
7 12 19
8 14 21
9 15 21
10 17 25
200 200 200
250 250 280
300 320 340
\ No newline at end of file
unix_timestamp Accel._X Accel._Y Accel._Z Battery Bottom_Rotor CPU_Load Ground_Dist. Gyro_Phi Gyro_Psi Gyro_Theta Left_Servo Mag._X Mag._Y Mag._Z Pressure Right_Servo Temperature Top_Rotor pitch_IMU roll_IMU yaw_IMU
1270125571544 5 -197 982 0 29685 29866 29888 0 0 0 96186 354 -0.112812 0.13585 -1.94192
1270125571564 6 -198 983 0 29781 29995 29871 0 0 0 96183 354 -0.112085 0.137193 -1.94139
1270125571584 10 -197 982 0 29739 30018 29867 0 0 0 96171 354 -0.111693 0.136574 -1.94353
1270125571604 7 -198 982 0 29802 29911 29803 0 0 0 96177 354 -0.112179 0.135778 -1.94617
1270125571645 4 -197 984 0 29782 29844 29844 0 0 0 96180 354 -0.113056 0.135965 -1.94715
1270125571665 4 -200 985 0 29685 29867 29884 0 0 0 96183 354 -0.113231 0.135327 -1.94586
1270125571685 7 -198 983 0 29757 30018 29829 0 0 0 96177 354 -0.112604 0.136857 -1.94508
1270125571706 6 -198 982 0 29759 29992 29867 0 0 0 96183 354 -0.1126 0.136602 -1.94915
1270125571746 7 -196 985 0 29803 29910 29800 0 0 0 96183 354 -0.112392 0.136709 -1.95079
1270125571766 4 -198 981 0 29750 29828 29888 0 0 0 96186 354 -0.113342 0.135532 -1.95064
1270125571787 5 -197 984 0 29759 29931 29881 0 0 0 96174 354 -0.112628 0.135657 -1.9488
1270125571807 10 -197 982 0 29739 29958 29819 0 0 0 96174 354 -0.112506 0.135777 -1.95001
1270125571847 4 -198 981 0 29786 29829 29864 0 0 0 96232 356 -0.112359 0.135253 -1.94825
1270125571867 5 -201 978 0 29719 29856 29890 0 0 0 96218 356 -0.11218 0.134669 -1.94657
1270125571888 7 -198 986 0 29782 29813 29845 0 0 0 96223 356 -0.111451 0.135688 -1.9455
1270125571908 10 -200 984 0 29693 30048 29885 0 0 0 96215 356 -0.110745 0.1365 -1.94668
1270125571948 5 -197 982 0 29757 29899 29844 0 0 0 96229 356 -0.110004 0.135859 -1.94573
1270125571969 6 -197 983 0 29727 29829 29814 0 0 0 96249 356 -0.110316 0.135751 -1.94565
1270125571989 6 -197 978 0 29790 29828 29815 0 0 0 96220 356 -0.111159 0.136244 -1.94416
1270125572009 5 -194 983 0 29718 29856 29890 0 0 0 96229 356 -0.111216 0.135992 -1.94196
1270125572050 3 -196 985 0 29739 29978 29827 0 0 0 96223 356 -0.110727 0.136577 -1.94402
1270125572070 8 -198 982 0 29782 29829 29815 0 0 0 96235 356 -0.111423 0.136697 -1.94566
1270125572090 8 -195 982 0 29687 29865 29894 0 0 0 96218 356 -0.112088 0.136097 -1.9442
1270125572130 8 -198 986 0 29793 29859 29844 0 0 0 96244 356 -0.110282 0.137491 -1.94235
1270125572171 6 -198 982 0 29790 29856 29879 0 0 0 96244 356 -0.112179 0.136971 -1.94365
1270125572191 3 -198 980 0 29759 30018 29829 0 0 0 96218 356 -0.111623 0.136194 -1.94286
1270125572211 7 -198 984 0 29758 29829 29846 0 0 0 96229 356 -0.112275 0.136007 -1.94387
1270125572252 8 -197 980 0 29743 30018 29824 0 0 0 96215 356 -0.111515 0.135539 -1.94281
1270125572272 11 -195 984 0 29741 29867 29844 0 0 0 96249 356 -0.111995 0.135753 -1.94527
1270125572292 4 -200 984 0 29771 29980 29865 0 0 0 96215 356 -0.111913 0.135829 -1.94455
1270125572312 6 -198 983 0 29792 29837 29845 0 0 0 96229 356 -0.111884 0.134861 -1.94478
1270125572353 5 -196 983 0 29685 29867 29884 0 0 0 96238 356 -0.111332 0.135644 -1.94784
1270125572373 5 -198 982 0 29693 29852 29904 0 0 0 96238 356 -0.110772 0.136927 -1.94698
1270125572393 6 -195 982 0 29738 29791 29818 0 0 0 96229 356 -0.109851 0.138106 -1.94592
1270125572414 8 -198 986 0 29782 29844 29829 0 0 0 96223 356 -0.111077 0.137396 -1.9428
1270125572454 11 -198 983 0 29743 29986 29833 0 0 0 96220 356 -0.110257 0.136744 -1.94155
1270125572474 6 -198 983 0 29749 29866 29813 0 0 0 96223 356 -0.110497 0.136917 -1.94351
1270125572495 6 -197 984 0 29719 29828 29890 0 0 0 96223 356 -0.111349 0.136959 -1.94295
1270125572515 7 -197 983 0 29760 29791 29818 0 0 0 96232 356 -0.111323 0.137251 -1.93972
1270125572555 10 -198 984 0 29800 30016 29857 0 0 0 96241 356 -0.110873 0.137041 -1.94196
1270125572575 5 -200 982 0 29760 29962 29866 0 0 0 96232 356 -0.110648 0.136038 -1.9445
1270125572596 4 -197 983 0 29740 30024 29867 0 0 0 96238 356 -0.110486 0.136046 -1.94576
1270125572616 8 -196 985 0 29802 29783 29808 0 0 0 96235 356 -0.111227 0.135128 -1.94567
1270125572656 5 -198 986 0 29771 29972 29867 0 0 0 96229 356 -0.111182 0.133833 -1.94823
1270125572697 8 -196 980 0 29739 29978 29803 0 0 0 96238 356 -0.111457 0.133602 -1.94682
1270125572717 4 -196 983 0 29749 30026 29867 0 0 0 96235 356 -0.116038 0.131922 -1.93861
1270125592944 5 -195 985 0 29757 29994 29871 0 0 0 96220 356 -0.115848 0.1323 -1.93916
1270125593025 5 -200 986 0 29780 29844 29845 0 0 0 96235 356 -0.115273 0.132222 -1.93576
1270125593045 5 -197 982 0 29757 29995 29871 0 0 0 96229 356 -0.114713 0.132137 -1.93723
1270125593086 4 -197 984 0 29802 29847 29819 0 0 0 96241 356 -0.114815 0.131529 -1.93626
1270125593106 6 -202 984 0 29802 29783 29803 0 0 0 96247 356 -0.115379 0.130754 -1.93546
1270125593126 8 -196 982 0 29803 29918 29793 0 0 0 96229 356 -0.116136 0.130336 -1.93339
1270125593146 6 -196 987 0 29802 29825 29802 0 0 0 96244 356 -0.117635 0.128822 -1.93292
1270125593187 7 -197 978 0 29802 29825 29864 0 0 0 96238 356 -0.117592 0.128252 -1.93468
1270125593207 7 -197 980 0 29803 29918 29771 0 0 0 96235 356 -0.116961 0.127734 -1.93337
1270125593227 6 -200 982 0 29733 29994 29867 0 0 0 96241 356 -0.11821 0.127208 -1.93399
1270125593247 7 -194 984 0 29739 29982 29888 0 0 0 96235 356 -0.116428 0.128791 -1.9378
1270125593288 10 -197 985 0 29771 30000 29865 0 0 0 96238 356 -0.116243 0.128666 -1.93672
\ No newline at end of file
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