Commit 38941da9 authored by pixhawk's avatar pixhawk

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

Added new options for windows serial port, fixed a number of bugs, added customizing options to instrument widgets
parent fd99a0e0
......@@ -12,6 +12,7 @@ cp -r ../bin/mac/qgroundcontrol.app mac/.
cp -r ../audio mac/qgroundcontrol.app/Contents/MacOs/.
mkdir -p mac/qgroundcontrol.app/Contents/Frameworks/
# SDL is not copied by Qt - for whatever reason
cp -r SDL.framework mac/qgroundcontrol.app/Contents/Frameworks/.
echo -e '\n\nStarting to create disk image. This may take a while..\n'
macdeployqt mac/qgroundcontrol.app -dmg
......
......@@ -29,6 +29,7 @@
# $$BASEDIR/lib/openjaus/libopenJaus/include
message(Qt version $$[QT_VERSION])
message(Using Qt from $QTDIR)
release {
# DEFINES += QT_NO_DEBUG_OUTPUT
......@@ -50,6 +51,7 @@ macx {
contains( HARDWARE_PLATFORM, 9.6.0 ) || contains( HARDWARE_PLATFORM, 9.7.0 ) || contains( HARDWARE_PLATFORM, 9.8.0 ) || contains( HARDWARE_PLATFORM, 9.9.0 ) {
# x86 Mac OS X Leopard 10.5 and earlier
CONFIG += x86 cocoa phonon
CONFIG -= x86_64
message(Building for Mac OS X 32bit/Leopard 10.5 and earlier)
# Enable function-profiling with the OS X saturn tool
......
......@@ -11,6 +11,7 @@ namespace QGC
const QColor colorGreen(20, 200, 20);
const QColor colorYellow(255, 255, 0);
const QColor colorDarkYellow(180, 180, 0);
const QColor colorBackground("#050508");
/** @brief Get the current ground time in microseconds */
quint64 groundTimeUsecs();
......
......@@ -289,16 +289,19 @@ void MAVLinkSimulationLink::mainloop()
if (keys.value(i, "") == "Gyro_Phi")
{
rawImuValues.xgyro = d;
attitude.rollspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
}
if (keys.value(i, "") == "Gyro_Theta")
{
rawImuValues.ygyro = d;
attitude.pitchspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
}
if (keys.value(i, "") == "Gyro_Psi")
{
rawImuValues.zgyro = d;
attitude.yawspeed = ((d-29.000)/3000.0)*2.7-2.7-2.65;
}
#ifdef MAVLINK_ENABLED_PIXHAWK
if (keys.value(i, "") == "Pressure")
......@@ -426,12 +429,12 @@ void MAVLinkSimulationLink::mainloop()
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// GLOBAL POSITION VEHICLE 3
mavlink_msg_global_position_int_pack(60, componentId, &ret, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// // GLOBAL POSITION VEHICLE 3
// mavlink_msg_global_position_int_pack(60, componentId, &ret, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
// bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
// //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength);
// streampointer += bufferlength;
static int rcCounter = 0;
if (rcCounter == 2)
......@@ -609,15 +612,15 @@ void MAVLinkSimulationLink::mainloop()
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// HEARTBEAT VEHICLE 3
// // HEARTBEAT VEHICLE 3
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// // Pack message and get size of encoded byte string
// messageSize = mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// // Allocate buffer with packet data
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength);
// streampointer += bufferlength;
// STATUS VEHICLE 2
mavlink_sys_status_t status2;
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
......@@ -58,34 +38,16 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
// Load defaults from settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.sync();
if (settings.contains("SERIALLINK_COMM_PORT"))
{
this->porthandle = settings.value("SERIALLINK_COMM_PORT").toString();
}
// *nix (Linux, MacOS tested) serial port support
port = new QextSerialPort(porthandle, QextSerialPort::Polling);
//port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
if (settings.contains("SERIALLINK_COMM_PORT"))
{
setBaudRate(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
setDataBitsType(settings.value("SERIALLINK_COMM_DATABITS").toInt());
}
else
{
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
}
port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
port->setBaudRate(baudrate);
port->setFlowControl(flow);
......@@ -96,7 +58,7 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
// Set the port name
if (porthandle == "")
{
// name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)");
// name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)");
name = tr("Serial Link ") + QString::number(getId());
}
else
......@@ -134,6 +96,33 @@ SerialLink::~SerialLink()
port = NULL;
}
void SerialLink::loadSettings()
{
// Load defaults from settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.sync();
if (settings.contains("SERIALLINK_COMM_PORT"))
{
setPortName(settings.value("SERIALLINK_COMM_PORT").toString());
setBaudRateType(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
setDataBitsType(settings.value("SERIALLINK_COMM_DATABITS").toInt());
}
}
void SerialLink::writeSettings()
{
// Store settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
settings.setValue("SERIALLINK_COMM_BAUD", getBaudRateType());
settings.setValue("SERIALLINK_COMM_PARITY", getParityType());
settings.setValue("SERIALLINK_COMM_STOPBITS", getStopBitsType());
settings.setValue("SERIALLINK_COMM_DATABITS", getDataBitsType());
settings.sync();
}
/**
* @brief Runs the thread
......@@ -189,13 +178,13 @@ void SerialLink::writeBytes(const char* data, qint64 size)
// Increase write counter
bitsSentTotal += size * 8;
// int i;
// for (i=0; i<size; i++)
// {
// unsigned char v=data[i];
// int i;
// for (i=0; i<size; i++)
// {
// unsigned char v=data[i];
// //fprintf(stderr,"%02x ", v);
// }
// //fprintf(stderr,"%02x ", v);
// }
}
}
......@@ -321,18 +310,12 @@ bool SerialLink::hardwareConnect()
statisticsMutex.unlock();
bool connectionUp = isConnected();
if(connectionUp) {
if(connectionUp)
{
emit connected();
emit connected(true);
// Store settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
settings.setValue("SERIALLINK_COMM_BAUD", getBaudRate());
settings.setValue("SERIALLINK_COMM_PARITY", getParityType());
settings.setValue("SERIALLINK_COMM_STOPBITS", getStopBitsType());
settings.setValue("SERIALLINK_COMM_DATABITS", getDataBitsType());
settings.sync();
writeSettings();
}
return connectionUp;
......@@ -376,7 +359,8 @@ void SerialLink::setName(QString name)
qint64 SerialLink::getNominalDataRate()
{
qint64 dataRate = 0;
switch (baudrate) {
switch (baudrate)
{
case BAUD50:
dataRate = 50;
break;
......@@ -442,6 +426,13 @@ qint64 SerialLink::getNominalDataRate()
break;
case BAUD256000:
dataRate = 256000;
// Windows-specific high-end baudrates
case BAUD230400:
dataRate = 230400;
case BAUD460800:
dataRate = 460800;
case BAUD921600:
dataRate = 921600;
break;
}
return dataRate;
......@@ -543,7 +534,8 @@ bool SerialLink::setPortName(QString portName)
if(portName.trimmed().length() > 0)
{
bool reconnect = false;
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
......@@ -650,8 +642,17 @@ bool SerialLink::setBaudRateType(int rateIndex)
baudrate = BAUD128000;
break;
case 21:
baudrate = BAUD230400;
break;
case 22:
baudrate = BAUD256000;
break;
case 23:
baudrate = BAUD460800;
break;
case 24:
baudrate = BAUD921600;
break;
default:
// If none of the above cases matches, there must be an error
accepted = false;
......@@ -671,12 +672,14 @@ bool SerialLink::setBaudRate(int rate)
{
bool reconnect = false;
bool accepted = true; // This is changed if none of the data rates matches
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
switch (rate) {
switch (rate)
{
case 50:
baudrate = BAUD50;
break;
......@@ -740,9 +743,18 @@ bool SerialLink::setBaudRate(int rate)
case 128000:
baudrate = BAUD128000;
break;
case 230400:
baudrate = BAUD230400;
break;
case 256000:
baudrate = BAUD256000;
break;
case 460800:
baudrate = BAUD460800;
break;
case 921600:
baudrate = BAUD921600;
break;
default:
// If none of the above cases matches, there must be an error
accepted = false;
......@@ -765,12 +777,14 @@ bool SerialLink::setFlowType(int flow)
{
bool reconnect = false;
bool accepted = true;
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
switch (flow) {
switch (flow)
{
case FLOW_OFF:
this->flow = FLOW_OFF;
break;
......@@ -794,12 +808,14 @@ bool SerialLink::setParityType(int parity)
{
bool reconnect = false;
bool accepted = true;
if(isConnected()) {
if(isConnected())
{
disconnect();
reconnect = true;
}
switch (parity) {
switch (parity)
{
case PAR_NONE:
this->parity = PAR_NONE;
break;
......@@ -826,11 +842,14 @@ bool SerialLink::setParityType(int parity)
return accepted;
}
// FIXME Works not as anticipated by user!
bool SerialLink::setDataBitsType(int dataBits)
{
bool accepted = true;
switch (dataBits) {
switch (dataBits)
{
case 5:
this->dataBits = DATA_5;
break;
......@@ -858,6 +877,7 @@ bool SerialLink::setDataBitsType(int dataBits)
return accepted;
}
// FIXME WORKS NOT AS ANTICIPATED BY USER!
bool SerialLink::setStopBitsType(int stopBits)
{
bool reconnect = false;
......@@ -867,7 +887,8 @@ bool SerialLink::setStopBitsType(int stopBits)
reconnect = true;
}
switch (stopBits) {
switch (stopBits)
{
case 1:
this->stopBits = STOP_1;
break;
......
......@@ -91,6 +91,9 @@ public:
qint64 getBitsSent();
qint64 getBitsReceived();
void loadSettings();
void writeSettings();
void run();
int getLinkQuality();
......
......@@ -57,6 +57,8 @@ public slots:
virtual bool setParityType(int parity) = 0;
virtual bool setDataBitsType(int dataBits) = 0;
virtual bool setStopBitsType(int stopBits) = 0;
virtual void loadSettings() = 0;
virtual void writeSettings() = 0;
};
......
......@@ -41,7 +41,7 @@ This constructor assigns the device name to the name of the first port on the sp
See the other constructors if you need to open a different port.
*/
Posix_QextSerialPort::Posix_QextSerialPort(QextSerialBase::QueryMode mode)
: QextSerialBase()
: QextSerialBase()
{
setQueryMode(mode);
init();
......@@ -123,7 +123,7 @@ Posix_QextSerialPort::Posix_QextSerialPort(const QString & name, const PortSetti
Override the = operator.
*/
Posix_QextSerialPort& Posix_QextSerialPort::operator=(const Posix_QextSerialPort& s)
{
{
setOpenMode(s.openMode());
port = s.port;
Settings.BaudRate=s.Settings.BaudRate;
......@@ -194,7 +194,10 @@ BAUD1800.
BAUD76800 57600 76800
*BAUD115200 115200 115200
BAUD128000 128000 115200
BAUD230400 230400 115200
BAUD256000 256000 115200
BAUD460800 460800 115200
BAUD921600 921600 115200
\endverbatim
*/
void Posix_QextSerialPort::setBaudRate(BaudRateType baudRate)
......@@ -220,6 +223,9 @@ void Posix_QextSerialPort::setBaudRate(BaudRateType baudRate)
break;
case BAUD128000:
case BAUD230400:
case BAUD460800:
case BAUD921600:
case BAUD256000:
Settings.BaudRate=BAUD115200;
break;
......@@ -486,8 +492,11 @@ void Posix_QextSerialPort::setBaudRate(BaudRateType baudRate)
break;
/*256000 baud*/
case BAUD230400:
case BAUD460800:
case BAUD921600:
case BAUD256000:
TTY_WARNING("Posix_QextSerialPort: POSIX does not support 256000 baud operation. Switching to 115200 baud.");
TTY_WARNING("Posix_QextSerialPort: POSIX does not support baud rates above 115200 baud. Switching to 115200 baud.");
#ifdef CBAUD
Posix_CommConfig.c_cflag&=(~CBAUD);
Posix_CommConfig.c_cflag|=B115200;
......
......@@ -92,8 +92,11 @@ enum BaudRateType
BAUD57600,
BAUD76800, //POSIX ONLY
BAUD115200,
BAUD128000, //WINDOWS ONLY
BAUD256000 //WINDOWS ONLY
BAUD128000, // WINDOWS ONLY
BAUD230400, // WINDOWS ONLY
BAUD256000, // WINDOWS ONLY
BAUD460800, // WINDOWS ONLY
BAUD921600 // WINDOWS ONLY
};
enum DataBitsType
......
......@@ -713,6 +713,10 @@ are speeds that are usable on both Windows and POSIX.
*BAUD115200 115200 115200
BAUD128000 128000 115200
BAUD256000 256000 115200
BAUD230400 230400 115200
BAUD256000 256000 115200
BAUD460800 460800 115200
BAUD921600 921600 115200
\endverbatim
*/
void Win_QextSerialPort::setBaudRate(BaudRateType baudRate) {
......@@ -863,6 +867,21 @@ void Win_QextSerialPort::setBaudRate(BaudRateType baudRate) {
TTY_PORTABILITY_WARNING("Win_QextSerialPort Portability Warning: POSIX does not support 256000 baud operation.");
Win_CommConfig.dcb.BaudRate=CBR_256000;
break;
/*230400 baud*/
case BAUD230400:
TTY_PORTABILITY_WARNING("Win_QextSerialPort Portability Warning: POSIX does not support 230400 baud operation.");
Win_CommConfig.dcb.BaudRate=CBR_230400;
break;
/*460800 baud*/
case BAUD460800:
TTY_PORTABILITY_WARNING("Win_QextSerialPort Portability Warning: POSIX does not support 460800 baud operation.");
Win_CommConfig.dcb.BaudRate=CBR_460800;
break;
/*921600 baud*/
case BAUD921600:
TTY_PORTABILITY_WARNING("Win_QextSerialPort Portability Warning: POSIX does not support 921600 baud operation.");
Win_CommConfig.dcb.BaudRate=CBR_921600;
break;
}
SetCommConfig(Win_Handle, &Win_CommConfig, sizeof(COMMCONFIG));
}
......
/*=====================================================================
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/>.
/*===================================================================
======================================================================*/
/**
......@@ -48,46 +28,46 @@ This file is part of the QGROUNDCONTROL project
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(*this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
currentVoltage(12.0f),
lpVoltage(12.0f),
mode(MAV_MODE_UNINIT),
status(MAV_STATE_UNINIT),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
receiveDropRate(0),
sendDropRate(0),
lowBattAlarm(false),
positionLock(false),
localX(0.0),
localY(0.0),
localZ(0.0),
latitude(0.0),
longitude(0.0),
altitude(0.0),
roll(0.0),
pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)),
paramsOnceRequested(false)
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(*this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
currentVoltage(12.0f),
lpVoltage(12.0f),
mode(MAV_MODE_UNINIT),
status(MAV_STATE_UNINIT),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
receiveDropRate(0),
sendDropRate(0),
lowBattAlarm(false),
positionLock(false),
localX(0.0),
localY(0.0),
localZ(0.0),
latitude(0.0),
longitude(0.0),
altitude(0.0),
roll(0.0),
pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)),
paramsOnceRequested(false)
{
color = UASInterface::getNextColor();
setBattery(LIPOLY, 3);
......@@ -134,14 +114,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (!links->contains(link))
{
addLink(link);
// qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
// qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
}
// else
// {
// qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
// }
// else
// {
// qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
// }
// qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
// qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
if (message.sysid == uasId)
{
......@@ -188,7 +168,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status);
emit loadChanged(this,state.load/10.0f);
emit UAS::valueChanged(this, "Load", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
emit UAS::valueChanged(uasId, "Load", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
stateAudio = " changed status to " + uasState;
}
......@@ -289,9 +269,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Accel. X", raw.xacc, time);
emit valueChanged(uasId, "Accel. Y", raw.yacc, time);
emit valueChanged(uasId, "Accel. Z", raw.zacc, time);
emit valueChanged(uasId, "Gyro Phi", raw.xgyro, time);
emit valueChanged(uasId, "Gyro Theta", raw.ygyro, time);
emit valueChanged(uasId, "Gyro Psi", raw.zgyro, time);
emit valueChanged(uasId, "Gyro Phi", static_cast<double>(raw.xgyro), time);
emit valueChanged(uasId, "Gyro Theta", static_cast<double>(raw.ygyro), time);
emit valueChanged(uasId, "Gyro Psi", static_cast<double>(raw.zgyro), time);
emit valueChanged(uasId, "Mag. X", raw.xmag, time);
emit valueChanged(uasId, "Mag. Y", raw.ymag, time);
emit valueChanged(uasId, "Mag. Z", raw.zmag, time);
......@@ -307,15 +287,24 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
roll = attitude.roll;
pitch = attitude.pitch;
yaw = attitude.yaw;
// emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
// emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
// emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
emit valueChanged(this, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
emit valueChanged(this, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
emit valueChanged(this, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
emit valueChanged(uasId, "rollspeed IMU", attitude.rollspeed, time);
emit valueChanged(uasId, "pitchspeed IMU", attitude.pitchspeed, time);
emit valueChanged(uasId, "yawspeed IMU", attitude.yawspeed, time);
// Emit in angles
emit valueChanged(uasId, "roll (deg)", (attitude.roll/M_PI)*180.0, time);
emit valueChanged(uasId, "pitch (deg)", (attitude.pitch/M_PI)*180.0, time);
emit valueChanged(uasId, "yaw (deg)", (attitude.yaw/M_PI)*180.0, time);
emit valueChanged(uasId, "roll V (deg/s)", (attitude.rollspeed/M_PI)*180.0, time);
emit valueChanged(uasId, "pitch V (deg/s)", (attitude.pitchspeed/M_PI)*180.0, time);
emit valueChanged(uasId, "yaw V (deg/s)", (attitude.yawspeed/M_PI)*180.0, time);
emit attitudeChanged(this, mavlink_msg_attitude_get_roll(&message), mavlink_msg_attitude_get_pitch(&message), mavlink_msg_attitude_get_yaw(&message), time);
}
break;
......@@ -338,8 +327,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
// qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
// qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
// qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
//emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
// Set internal state
......@@ -441,6 +430,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// FIXME Emit to other components
}
break;
case MAVLINK_MSG_ID_RAW_PRESSURE:
{
mavlink_raw_pressure_t pressure;
mavlink_msg_raw_pressure_decode(&message, &pressure);
emit valueChanged(uasId, "Abs pressure", pressure.press_abs, this->getUnixTime(0));
emit valueChanged(uasId, "Diff pressure 1", pressure.press_diff1, this->getUnixTime(0));
emit valueChanged(uasId, "Diff pressure 2", pressure.press_diff2, this->getUnixTime(0));
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
{
mavlink_rc_channels_raw_t channels;
......@@ -612,22 +610,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, str+".z", vect.z, time);
}
break;
//#ifdef MAVLINK_ENABLED_PIXHAWK
// case MAVLINK_MSG_ID_POINT_OF_INTEREST:
// {
// mavlink_point_of_interest_t poi;
// mavlink_msg_point_of_interest_decode(&message, &poi);
// emit poiFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN), poi.x, poi.y, poi.z);
// }
// break;
// case MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION:
// {
// mavlink_point_of_interest_connection_t poi;
// mavlink_msg_point_of_interest_connection_decode(&message, &poi);
// emit poiConnectionFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN), poi.x1, poi.y1, poi.z1, poi.x2, poi.y2, poi.z2);
// }
// break;
//#endif
//#ifdef MAVLINK_ENABLED_PIXHAWK
// case MAVLINK_MSG_ID_POINT_OF_INTEREST:
// {
// mavlink_point_of_interest_t poi;
// mavlink_msg_point_of_interest_decode(&message, &poi);
// emit poiFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN), poi.x, poi.y, poi.z);
// }
// break;
// case MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION:
// {
// mavlink_point_of_interest_connection_t poi;
// mavlink_msg_point_of_interest_connection_decode(&message, &poi);
// emit poiConnectionFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN), poi.x1, poi.y1, poi.z1, poi.x2, poi.y2, poi.z2);
// }
// break;
//#endif
#ifdef MAVLINK_ENABLED_UALBERTA
case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
{
......@@ -720,16 +718,16 @@ void UAS::setLocalOriginAtCurrentGPSPosition()
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg;
mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
sendMessage(msg);
#else
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
#endif
#endif
}
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
......@@ -739,10 +737,10 @@ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
sendMessage(msg);
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
#endif
}
......@@ -1333,15 +1331,15 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
manualYawAngle = yaw * yawScaling;
manualThrust = thrust * thrustScaling;
// if(mode == (int)MAV_MODE_MANUAL)
// {
// if(mode == (int)MAV_MODE_MANUAL)
// {
mavlink_message_t message;
mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
sendMessage(message);
qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
// }
// }
}
int UAS::getSystemType()
......@@ -1363,7 +1361,7 @@ void UAS::receiveButton(int buttonIndex)
break;
}
// qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
// qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
}
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK 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.
PIXHAWK 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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......@@ -33,7 +13,11 @@ This file is part of the PIXHAWK project
#include <QGLWidget>
#include <QStringList>
#include <QGraphicsTextItem>
#include <QDockWidget>
#include <QInputDialog>
#include <QMouseEvent>
#include <QMenu>
#include <QSettings>
#include "UASManager.h"
#include "HDDisplay.h"
#include "ui_HDDisplay.h"
......@@ -44,7 +28,7 @@ This file is part of the PIXHAWK project
#endif
#include <QDebug>
HDDisplay::HDDisplay(QStringList* plotList, QWidget *parent) :
HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
QGraphicsView(parent),
uas(NULL),
values(QMap<QString, float>()),
......@@ -73,52 +57,61 @@ HDDisplay::HDDisplay(QStringList* plotList, QWidget *parent) :
strongStrokeWidth(1.5f),
normalStrokeWidth(1.0f),
fineStrokeWidth(0.5f),
acceptList(plotList),
acceptList(new QStringList()),
lastPaintTime(0),
columns(3),
m_ui(new Ui::HDDisplay)
{
setWindowTitle(title);
//m_ui->setupUi(this);
// Check if acceptlist exists
if (!acceptList)
// Add all items in accept list to gauge
if (plotList)
{
acceptList = new QStringList();
for(int i = 0; i < plotList->length(); ++i)
{
addGauge(plotList->at(i));
}
}
// setBackgroundBrush(QBrush(backgroundColor));
// setDragMode(QGraphicsView::ScrollHandDrag);
// setCacheMode(QGraphicsView::CacheBackground);
// // FIXME Handle full update with care - ressource intensive
// setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
//
// setRenderHints(QPainter::Antialiasing | QPainter::SmoothPixmapTransform);
//
// //Set-up the scene
// QGraphicsScene* Scene = new QGraphicsScene(this);
// setScene(Scene);
//
// //Populate the scene
// for(int x = 0; x < 1000; x = x + 25) {
// for(int y = 0; y < 1000; y = y + 25) {
//
// if(x % 100 == 0 && y % 100 == 0) {
// Scene->addRect(x, y, 2, 2);
//
// QString pointString;
// QTextStream stream(&pointString);
// stream << "(" << x << "," << y << ")";
// QGraphicsTextItem* item = Scene->addText(pointString);
// item->setPos(x, y);
// } else {
// Scene->addRect(x, y, 1, 1);
// }
// }
// }
//
// //Set-up the view
// setSceneRect(0, 0, 1000, 1000);
// setCenter(QPointF(500.0, 500.0)); //A modified version of centerOn(), handles special cases
// setCursor(Qt::OpenHandCursor);
restoreState();
createActions();
// setBackgroundBrush(QBrush(backgroundColor));
// setDragMode(QGraphicsView::ScrollHandDrag);
// setCacheMode(QGraphicsView::CacheBackground);
// // FIXME Handle full update with care - ressource intensive
// setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
//
// setRenderHints(QPainter::Antialiasing | QPainter::SmoothPixmapTransform);
//
// //Set-up the scene
// QGraphicsScene* Scene = new QGraphicsScene(this);
// setScene(Scene);
//
// //Populate the scene
// for(int x = 0; x < 1000; x = x + 25) {
// for(int y = 0; y < 1000; y = y + 25) {
//
// if(x % 100 == 0 && y % 100 == 0) {
// Scene->addRect(x, y, 2, 2);
//
// QString pointString;
// QTextStream stream(&pointString);
// stream << "(" << x << "," << y << ")";
// QGraphicsTextItem* item = Scene->addText(pointString);
// item->setPos(x, y);
// } else {
// Scene->addRect(x, y, 1, 1);
// }
// }
// }
//
// //Set-up the view
// setSceneRect(0, 0, 1000, 1000);
// setCenter(QPointF(500.0, 500.0)); //A modified version of centerOn(), handles special cases
// setCursor(Qt::OpenHandCursor);
this->setMinimumHeight(125);
......@@ -147,12 +140,13 @@ HDDisplay::HDDisplay(QStringList* plotList, QWidget *parent) :
HDDisplay::~HDDisplay()
{
saveState();
delete m_ui;
}
void HDDisplay::enableGLRendering(bool enable)
{
Q_UNUSED(enable)
Q_UNUSED(enable);
}
void HDDisplay::triggerUpdate()
......@@ -170,6 +164,172 @@ void HDDisplay::paintEvent(QPaintEvent * event)
renderOverlay();
}
void HDDisplay::contextMenuEvent (QContextMenuEvent* event)
{
QMenu menu(this);
menu.addAction(addGaugeAction);
menu.addActions(getItemRemoveActions());
menu.addSeparator();
menu.addAction(setColumnsAction);
menu.addAction(setTitleAction);
menu.exec(event->globalPos());
}
void HDDisplay::saveState()
{
QSettings settings;
QString instruments;
// Restore instrument settings
for (int i = 0; i < acceptList->count(); i++)
{
QString key = acceptList->at(i);
instruments += "|" + QString::number(minValues.value(key, -1.0))+","+key+","+QString::number(maxValues.value(key, +1.0));
}
qDebug() << "Saving" << instruments;
settings.setValue(windowTitle()+"_gauges", instruments);
settings.sync();
}
void HDDisplay::restoreState()
{
QSettings settings;
settings.sync();
QStringList instruments = settings.value(windowTitle()+"_gauges").toString().split('|');
for (int i = 0; i < instruments.count(); i++)
{
addGauge(instruments.at(i));
}
}
QList<QAction*> HDDisplay::getItemRemoveActions()
{
QList<QAction*> actions;
for(int i = 0; i < acceptList->length(); ++i)
{
QString gauge = acceptList->at(i);
QAction* remove = new QAction(tr("Remove %1 gauge").arg(gauge), this);
remove->setStatusTip(tr("Removes the %1 gauge from the view.").arg(gauge));
remove->setData(gauge);
connect(remove, SIGNAL(triggered()), this, SLOT(removeItemByAction()));
actions.append(remove);
}
return actions;
}
void HDDisplay::removeItemByAction()
{
QAction* trigger = qobject_cast<QAction*>(QObject::sender());
if (trigger)
{
QString item = trigger->data().toString();
int index = acceptList->indexOf(item);
acceptList->removeAt(index);
minValues.remove(item);
maxValues.remove(item);
}
}
void HDDisplay::addGauge()
{
QStringList items;
for (int i = 0; i < values.count(); ++i)
{
items.append(QString("%1,%2,%3").arg("-180").arg(values.keys().at(i)).arg("+180"));
}
bool ok;
QString item = QInputDialog::getItem(this, tr("Add Gauge Instrument"),
tr("Format: min, curve name, max"), items, 0, true, &ok);
if (ok && !item.isEmpty())
{
addGauge(item);
}
}
void HDDisplay::addGauge(const QString& gauge)
{
if (gauge.length() > 0)
{
QStringList parts = gauge.split(',');
if (parts.count() > 1)
{
double val;
bool ok;
QString key = parts.at(1);
if (!acceptList->contains(key))
{
// Convert min to double number
val = parts.first().toDouble(&ok);
if (ok) minValues.insert(key, val);
// Convert max to double number
val = parts.last().toDouble(&ok);
if (ok) maxValues.insert(key, val);
// Add value to acceptlist
acceptList->append(key);
}
}
else
{
if (!acceptList->contains(gauge))
{
acceptList->append(parts.first());
}
}
}
}
void HDDisplay::createActions()
{
addGaugeAction = new QAction(tr("New &Gauge"), this);
addGaugeAction->setStatusTip(tr("Add a new gauge to the view by adding its name from the linechart"));
connect(addGaugeAction, SIGNAL(triggered()), this, SLOT(addGauge()));
setTitleAction = new QAction(tr("Set Widget Title"), this);
setTitleAction->setStatusTip(tr("Set the title caption of this tool widget"));
connect(setTitleAction, SIGNAL(triggered()), this, SLOT(setTitle()));
setColumnsAction = new QAction(tr("Set Number of Instrument Columns"), this);
setColumnsAction->setStatusTip(tr("Set number of columns to draw"));
connect(setColumnsAction, SIGNAL(triggered()), this, SLOT(setColumns()));
}
void HDDisplay::setColumns()
{
bool ok;
int i = QInputDialog::getInt(this, tr("Number of Instrument Columns"),
tr("Columns:"), columns, 1, 15, 1, &ok);
if (ok)
{
columns = i;
}
}
void HDDisplay::setColumns(int cols)
{
columns = cols;
}
void HDDisplay::setTitle()
{
QDockWidget* parent = dynamic_cast<QDockWidget*>(this->parentWidget());
if (parent)
{
bool ok;
QString text = QInputDialog::getText(this, tr("New title"),
tr("Widget title:"), QLineEdit::Normal,
parent->windowTitle(), &ok);
if (ok && !text.isEmpty())
parent->setWindowTitle(text);
this->setWindowTitle(text);
}
}
void HDDisplay::renderOverlay()
{
#if (QGC_EVENTLOOP_DEBUG)
......@@ -188,6 +348,13 @@ void HDDisplay::renderOverlay()
// Update scaling factor
// adjust scaling to fit both horizontally and vertically
scalingFactor = this->width()/vwidth;
// Adjust vheight dynamically according to the number of rows
float vColWidth = vwidth / columns;
int vRows = ceil(acceptList->length()/(float)columns);
// Assuming square instruments, vheight is column width*row count
vheight = vColWidth * vRows;
double scalingFactorH = this->height()/vheight;
if (scalingFactorH < scalingFactor) scalingFactor = scalingFactorH;
......@@ -195,7 +362,6 @@ void HDDisplay::renderOverlay()
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
//painter.fillRect(QRect(0, 0, width(), height()), backgroundColor);
const int columns = 3;
const float spacing = 0.4f; // 40% of width
const float gaugeWidth = vwidth / (((float)columns) + (((float)columns+1) * spacing + spacing * 0.5f));
const QColor gaugeColor = QColor(200, 200, 200);
......@@ -216,7 +382,7 @@ void HDDisplay::renderOverlay()
drawGauge(xCoord, yCoord, gaugeWidth/2.0f, minValues.value(value, -1.0f), maxValues.value(value, 1.0f), value, values.value(value, minValues.value(value, 0.0f)), gaugeColor, &painter, goodRanges.value(value, qMakePair(0.0f, 0.5f)), critRanges.value(value, qMakePair(0.7f, 1.0f)), true);
xCoord += gaugeWidth + leftSpacing;
// Move one row down if necessary
if (xCoord + gaugeWidth > vwidth)
if (xCoord + gaugeWidth*0.9f > vwidth)
{
yCoord += topSpacing + gaugeWidth;
xCoord = leftSpacing + gaugeWidth/2.0f;
......@@ -234,14 +400,14 @@ void HDDisplay::setActiveUAS(UASInterface* uas)
if (this->uas != NULL)
{
// Disconnect any previously connected active MAV
disconnect(this->uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
disconnect(this->uas, SIGNAL(valueChanged(int,QString,double,quint64)), this, SLOT(updateValue(int,QString,double,quint64)));
}
// Now connect the new UAS
//qDebug() << "UAS SET!" << "ID:" << uas->getUASID();
// Setup communication
connect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), this, SLOT(updateValue(int,QString,double,quint64)));
this->uas = uas;
}
......@@ -344,9 +510,14 @@ void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float
// per max. change
const float rangeScale = ((2.0f * M_PI) / (max - min)) * 0.72f;
const float nameHeight = radius / 2.5f;
const float scaledValue = (value-min)*rangeScale;
float nameHeight = radius / 2.6f;
paintText(name.toUpper(), color, nameHeight*0.7f, xRef-radius, yRef-radius, painter);
// Ensure some space
nameHeight *= 1.2f;
if (!solid)
{
circlePen.setStyle(Qt::DotLine);
......@@ -359,18 +530,17 @@ void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float
//drawCircle(xRef, yRef+nameHeight, radius, 0.0f, 170.0f, 1.0f, color, painter);
QString label;
label.sprintf("%05.1f", value);
label.sprintf("% 06.1f", value);
// Text
// height
const float textHeight = radius/2.0f;
const float textX = xRef-radius/6.0f;
const float textHeight = radius/2.1f;
const float textX = xRef-radius/3.0f;
const float textY = yRef+radius/2.0f;
// Draw background rectangle
// FIXME add background color for use in instrument panel
QBrush brush(QColor(0, 0, 0), Qt::SolidPattern);
QBrush brush(QGC::colorBackground, Qt::SolidPattern);
painter->setBrush(brush);
painter->setPen(Qt::NoPen);
painter->drawRect(refToScreenX(xRef-radius/2.5f), refToScreenY(yRef+nameHeight+radius/4.0f), refToScreenX(radius+radius/2.0f), refToScreenY((radius - radius/4.0f)*1.2f));
......@@ -396,7 +566,7 @@ void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float
// Draw the value
//painter->setPen(textColor);
paintText(label, color, textHeight, textX, textY+nameHeight, painter);
paintText(label, QGC::colorCyan, textHeight, textX, textY+nameHeight, painter);
//paintText(label, color, ((radius - radius/3.0f)*1.1f), xRef-radius/2.5f, yRef+radius/3.0f, painter);
// Draw the needle
......@@ -414,7 +584,7 @@ void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float
p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef+nameHeight+radius * 0.05f));
rotatePolygonClockWiseRad(p, value*rangeScale+zeroRotation, QPointF(xRef, yRef+nameHeight));
rotatePolygonClockWiseRad(p, scaledValue+zeroRotation, QPointF(xRef, yRef+nameHeight));
QBrush indexBrush;
indexBrush.setColor(color);
......@@ -580,11 +750,9 @@ float HDDisplay::refLineWidthToPen(float line)
return line * 2.50f;
}
void HDDisplay::updateValue(UASInterface* uas, QString name, double value, quint64 msec)
void HDDisplay::updateValue(int uasId, QString name, double value, quint64 msec)
{
Q_UNUSED(uas);
//if (this->uas == uas)
//{
Q_UNUSED(uasId);
// Update mean
const float oldMean = valuesMean.value(name, 0.0f);
const int meanCount = valuesCount.value(name, 0);
......@@ -593,7 +761,6 @@ void HDDisplay::updateValue(UASInterface* uas, QString name, double value, quint
valuesDot.insert(name, (value - values.value(name, 0.0f)) / ((msec - lastUpdate.value(name, 0))/1000.0f));
values.insert(name, value);
lastUpdate.insert(name, msec);
//}
}
/**
......@@ -664,20 +831,17 @@ void HDDisplay::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event)
{
Q_UNUSED(event);
refreshTimer->start(updateInterval);
}
}
void HDDisplay::hideEvent(QHideEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event)
{
Q_UNUSED(event);
refreshTimer->stop();
}
saveState();
}
......
......@@ -37,6 +37,7 @@ This file is part of the QGROUNDCONTROL project
#include <QTimer>
#include <QFontDatabase>
#include <QMap>
#include <QContextMenuEvent>
#include <QPair>
#include <cmath>
......@@ -58,14 +59,31 @@ class HDDisplay : public QGraphicsView
{
Q_OBJECT
public:
HDDisplay(QStringList* plotList, QWidget *parent = 0);
HDDisplay(QStringList* plotList, QString title="", QWidget *parent = 0);
~HDDisplay();
public slots:
/** @brief Update a HDD value */
void updateValue(UASInterface* uas, QString name, double value, quint64 msec);
void updateValue(int uasId, QString name, double value, quint64 msec);
void setActiveUAS(UASInterface* uas);
/** @brief Removes a plot item by the action data */
void removeItemByAction();
/** @brief Bring up the menu to add a gauge */
void addGauge();
/** @brief Add a gauge using this spec string */
void addGauge(const QString& gauge);
/** @brief Set the title of this widget and any existing parent dock widget */
void setTitle();
/** @brief Set the number of colums via popup */
void setColumns();
/** @brief Set the number of colums */
void setColumns(int cols);
/** @brief Save the current layout and state to disk */
void saveState();
/** @brief Restore the last layout and state from disk */
void restoreState();
protected slots:
void enableGLRendering(bool enable);
//void render(QPainter* painter, const QRectF& target = QRectF(), const QRect& source = QRect(), Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio);
......@@ -73,10 +91,13 @@ protected slots:
void triggerUpdate();
protected:
void changeEvent(QEvent *e);
void paintEvent(QPaintEvent * event);
void changeEvent(QEvent* e);
void paintEvent(QPaintEvent* event);
void showEvent(QShowEvent* event);
void hideEvent(QHideEvent* event);
void contextMenuEvent(QContextMenuEvent* event);
QList<QAction*> getItemRemoveActions();
void createActions();
float refLineWidthToPen(float line);
float refToScreenX(float x);
float refToScreenY(float y);
......@@ -155,6 +176,11 @@ protected:
QStringList* acceptList; ///< Variable names to plot
quint64 lastPaintTime; ///< Last time this widget was refreshed
int columns; ///< Number of instrument columns
QAction* addGaugeAction; ///< Action adding a gauge
QAction* setTitleAction; ///< Action setting the title
QAction* setColumnsAction; ///< Action setting the number of columns
private:
Ui::HDDisplay *m_ui;
......
......@@ -46,7 +46,7 @@ This file is part of the QGROUNDCONTROL project
#include <QDebug>
HSIDisplay::HSIDisplay(QWidget *parent) :
HDDisplay(NULL, parent),
HDDisplay(NULL, "", parent),
gpsSatellites(),
satellitesUsed(0),
attXSet(0),
......
......@@ -207,17 +207,19 @@ void MainWindow::buildPxWidgets()
{
//FIXME: memory of acceptList will never be freed again
QStringList* acceptList = new QStringList();
acceptList->append("roll IMU");
acceptList->append("pitch IMU");
acceptList->append("yaw IMU");
acceptList->append("rollspeed IMU");
acceptList->append("pitchspeed IMU");
acceptList->append("yawspeed IMU");
acceptList->append("-180,roll (deg),+180");
acceptList->append("-180,pitch (deg),+180");
acceptList->append("-180,yaw (deg),+180");
acceptList->append("-500,roll V (deg/s),+500");
acceptList->append("-500,pitch V (deg/s),+500");
acceptList->append("-500,yaw V (deg/s),+500");
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList();
acceptList2->append("Battery");
acceptList2->append("Pressure");
acceptList2->append("0,Abs pressure,65500");
acceptList2->append("-2000,Accel. X, 2000");
acceptList2->append("-2000,Accel. Y, 2000");
if (!linechartWidget)
{
......@@ -296,15 +298,15 @@ void MainWindow::buildPxWidgets()
if (!headDown1DockWidget)
{
headDown1DockWidget = new QDockWidget(tr("System Stats"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
headDown1DockWidget = new QDockWidget(tr("Flight Display"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, "Flight Display", this) );
addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea);
}
if (!headDown2DockWidget)
{
headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, "Payload Status", this) );
addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget()), MENU_HDD_2, Qt::RightDockWidgetArea);
}
......
......@@ -234,6 +234,7 @@ userConfigured(false)
if(serialLink != 0)
{
serialLink->loadSettings();
this->link = serialLink;
// Setup the user interface according to link type
......
......@@ -159,11 +159,26 @@
<string>128000</string>
</property>
</item>
<item>
<property name="text">
<string>230400</string>
</property>
</item>
<item>
<property name="text">
<string>256000</string>
</property>
</item>
<item>
<property name="text">
<string>460800</string>
</property>
</item>
<item>
<property name="text">
<string>921600</string>
</property>
</item>
</widget>
</item>
<item row="2" column="0">
......
......@@ -72,7 +72,7 @@ public:
public slots:
void addCurve(QString curve);
void removeCurve(QString curve);
void appendData(int sysId, QString curve, double data, quint64 usec);
void appendData(int uasId, QString curve, double data, quint64 usec);
void takeButtonClick(bool checked);
void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position);
......
......@@ -231,7 +231,7 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event)
// Reloading the webpage, this resets Google Earth
gEarthInitialized = false;
QTimer::singleShot(3000, this, SLOT(initializeGoogleEarth()));
QTimer::singleShot(10000, this, SLOT(initializeGoogleEarth()));
}
else
{
......@@ -300,7 +300,7 @@ void QGCGoogleEarthView::initializeGoogleEarth()
qDebug() << "COULD NOT GET DOCUMENT OBJECT! Aborting";
}
#endif
QTimer::singleShot(3500, this, SLOT(initializeGoogleEarth()));
QTimer::singleShot(2500, this, SLOT(initializeGoogleEarth()));
return;
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment