Commit 8d1552b9 authored by pixhawk's avatar pixhawk

Merged

parents 6dd121cf c88d83e8
[rgb]
principal_point\x=313.67245
principal_point\y=264.06175
focal_length\x=527.44654
focal_length\y=527.40652
distortion\k1=0.20780
distortion\k2=-0.34320
distortion\k3=0.00139
distortion\k4=0.00061
distortion\k5=0.00000
principal_point\x=314.70228964
principal_point\y=264.30478827
focal_length\x=527.91246131
focal_length\y=527.91246131
distortion\k1=0.20496745
distortion\k2=-0.36341243
distortion\k3=0.00000000
distortion\k4=0.00000000
distortion\k5=0.00000000
[depth]
principal_point\x=313.23400
principal_point\y=246.13447
focal_length\x=587.62150
focal_length\y=587.51184
distortion\k1=0.01063
distortion\k2=-0.04479
distortion\k3=-0.00073
distortion\k4=0.00081
distortion\k5=0.00000
principal_point\x=311.88621344
principal_point\y=247.63447078
focal_length\x=593.89813561
focal_length\y=593.89813561
distortion\k1=0.00000000
distortion\k2=0.00000000
distortion\k3=0.00000000
distortion\k4=0.00000000
distortion\k5=0.00000000
[transform]
R11=0.99994
R12=0.00098102
R13=0.010900
R21=-0.00097894
R22=1.0
R23=-0.00019534
R33=-0.010900
R32=0.00018466
R33=0.99994
Tx=-0.02581986
Ty=-0.0130948
Tz=-0.0047681
R11=0.999982
R12=0.000556
R13=0.005927
R21=-0.000563
R22=0.999999
R23=0.001235
R33=-0.005926
R32=-0.001239
R33=0.999982
Tx=-0.024287
Ty=0.001018
Tz=-0.015195
baseline=0.06061
disparity_offset=1092.3403
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN""http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd"
<html>
<meta http-equiv="content-type" content="text/html; charset=utf-8" />
<head>
<meta http-equiv="content-type" content="text/html; charset=utf-8" />
<!-- <head> -->
<!-- QGroundControl -->
<title>QGroundControl Google Earth View</title>
<!-- *** Replace the key below below with your own API key, available at http://code.google.com/apis/maps/signup.html *** -->
......
This diff is collapsed.
......@@ -249,7 +249,9 @@ HEADERS += src/MG.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsVideoCamControl.h \
src/ui/SlugsPadCameraControl.h
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
......@@ -359,7 +361,9 @@ SOURCES += src/main.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsVideoCamControl.cpp \
src/ui/SlugsPadCameraControl.cpp
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")
......
......@@ -157,6 +157,9 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
**/
Core::~Core()
{
//mainWindow->storeSettings();
mainWindow->hide();
mainWindow->deleteLater();
// Delete singletons
delete LinkManager::instance();
delete UASManager::instance();
......
......@@ -14,6 +14,9 @@ namespace QGC
/** @brief Get the current ground time in microseconds */
quint64 groundTimeUsecs();
const QString APPNAME = "QGROUNDCONTROL";
const QString COMPANYNAME = "OPENMAV";
}
#endif // QGC_H
......@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include <QList>
#include <QApplication>
#include "LinkManager.h"
#include <iostream>
#include <QDebug>
......@@ -65,6 +66,7 @@ LinkManager::~LinkManager()
void LinkManager::add(LinkInterface* link)
{
if(!link) return;
links.append(link);
emit newLink(link);
}
......@@ -73,6 +75,7 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
{
// Connect link to protocol
// the protocol will receive new bytes from the link
if(!link || !protocol) return;
connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray)));
// Store the connection information in the protocol links map
protocolLinks.insertMulti(protocol, link);
......@@ -91,7 +94,8 @@ bool LinkManager::connectAll()
foreach (LinkInterface* link, links)
{
if(! link->connect()) allConnected = false;
if(!link) {}
else if(!link->connect()) allConnected = false;
}
return allConnected;
......@@ -103,7 +107,9 @@ bool LinkManager::disconnectAll()
foreach (LinkInterface* link, links)
{
if(! link->disconnect()) allDisconnected = false;
//static int i=0;
if(!link){}
else if(!link->disconnect()) allDisconnected = false;
}
return allDisconnected;
......@@ -111,14 +117,32 @@ bool LinkManager::disconnectAll()
bool LinkManager::connectLink(LinkInterface* link)
{
if(!link) return false;
return link->connect();
}
bool LinkManager::disconnectLink(LinkInterface* link)
{
if(!link) return false;
return link->disconnect();
}
bool LinkManager::removeLink(LinkInterface* link)
{
if(link)
{
for (int i=0; i < QList<LinkInterface*>(links).size(); i++)
{
if(link==links.at(i))
{
links.removeAt(i); //remove from link list
}
}
return true;
}
return false;
}
/**
* The access time is linear in the number of links.
*
......
......@@ -67,6 +67,8 @@ public slots:
void add(LinkInterface* link);
void addProtocol(LinkInterface* link, ProtocolInterface* protocol);
bool removeLink(LinkInterface* link);
bool connectAll();
bool connectLink(LinkInterface* link);
......
......@@ -159,7 +159,9 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
switch (heartbeat.autopilot)
{
case MAV_AUTOPILOT_GENERIC:
uas = new UAS(this, message.sysid);
// Connect this robot to the UAS object
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), uas, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
break;
......@@ -202,11 +204,15 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
break;
}
// Set the autopilot type
uas->setAutopilotType((int)heartbeat.autopilot);
// 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);
}
// Only count message if UAS exists for this message
......
......@@ -559,16 +559,17 @@ void MAVLinkSimulationLink::mainloop()
// Send controller states
uint8_t attControl = 1;
uint8_t posXYControl = 1;
uint8_t posZControl = 0;
uint8_t posYawControl = 1;
uint8_t gpsLock = 2;
uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock);
#ifdef MAVLINK_ENABLED_PIXHAWK
uint8_t attControl = 1;
uint8_t posXYControl = 1;
uint8_t posZControl = 0;
uint8_t posYawControl = 1;
uint8_t gpsLock = 2;
uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock);
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
#endif
......@@ -659,7 +660,7 @@ qint64 MAVLinkSimulationLink::bytesAvailable()
void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
qDebug() << "Simulation received " << size << " bytes from groundstation: ";
//qDebug() << "Simulation received " << size << " bytes from groundstation: ";
// Increase write counter
//bitsSentTotal += size * 8;
......@@ -837,9 +838,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
unsigned char v=data[i];
fprintf(stderr,"%02x ", v);
//fprintf(stderr,"%02x ", v);
}
fprintf(stderr,"\n");
//fprintf(stderr,"\n");
readyBufferMutex.lock();
for (int i = 0; i < streampointer; i++)
......
......@@ -85,7 +85,7 @@ public:
public slots:
void writeBytes(const char* data, qint64 size);
void readBytes();
void mainloop();
virtual void mainloop();
bool connectLink(bool connect);
......
#include "MAVLinkSwarmSimulationLink.h"
MAVLinkSwarmSimulationLink::MAVLinkSwarmSimulationLink(QObject *parent) :
MAVLinkSimulationLink()
{
}
void MAVLinkSwarmSimulationLink::mainloop()
{
}
#ifndef MAVLINKSWARMSIMULATIONLINK_H
#define MAVLINKSWARMSIMULATIONLINK_H
#include "MAVLinkSimulationLink.h"
class MAVLinkSwarmSimulationLink : public MAVLinkSimulationLink
{
Q_OBJECT
public:
explicit MAVLinkSwarmSimulationLink(QObject *parent = 0);
signals:
public slots:
void mainloop();
};
#endif // MAVLINKSWARMSIMULATIONLINK_H
......@@ -30,10 +30,13 @@ This file is part of the QGROUNDCONTROL project
#include <QTimer>
#include <QDebug>
#include <QSettings>
#include <QMutexLocker>
#include "SerialLink.h"
#include "LinkManager.h"
#include "QGC.h"
#include <MG.h>
#include <iostream>
#ifdef _WIN32
#include "windows.h"
#endif
......@@ -54,12 +57,41 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
#endif
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
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.
// 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);
port->setParity(parity);
port->setDataBits(dataBits);
port->setStopBits(stopBits);
// Set the port name
if (porthandle == "")
......@@ -88,15 +120,7 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
//some other error occurred. Inform user.
}
#else
// *nix (Linux, MacOS tested) serial port support
port = new QextSerialPort(porthandle, QextSerialPort::Polling);
//port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
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);
port->setParity(parity);
port->setDataBits(dataBits);
port->setStopBits(stopBits);
#endif
// Link is setup, register it with link manager
......@@ -106,7 +130,7 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
SerialLink::~SerialLink()
{
disconnect();
delete port;
if(port) delete port;
port = NULL;
}
......@@ -170,7 +194,7 @@ void SerialLink::writeBytes(const char* data, qint64 size)
{
unsigned char v=data[i];
fprintf(stderr,"%02x ", v);
//fprintf(stderr,"%02x ", v);
}
}
}
......@@ -239,6 +263,8 @@ bool SerialLink::disconnect()
port->close();
dataMutex.unlock();
if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect
bool closed = true;
//port->isOpen();
......@@ -298,6 +324,15 @@ bool SerialLink::hardwareConnect()
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();
}
return connectionUp;
......@@ -311,7 +346,14 @@ bool SerialLink::hardwareConnect()
**/
bool SerialLink::isConnected()
{
return port->isOpen();
if (port)
{
return port->isOpen();
}
else
{
return false;
}
}
int SerialLink::getId()
......@@ -516,7 +558,7 @@ bool SerialLink::setPortName(QString portName)
this->porthandle = "\\\\.\\" + this->porthandle;
}
#endif
delete port;
if(port) delete port;
port = new QextSerialPort(porthandle, QextSerialPort::Polling);
port->setBaudRate(baudrate);
......@@ -707,9 +749,16 @@ bool SerialLink::setBaudRate(int rate)
break;
}
port->setBaudRate(this->baudrate);
if(reconnect) connect();
return accepted;
if (port)
{
port->setBaudRate(this->baudrate);
if(reconnect) connect();
return accepted;
}
else
{
return false;
}
}
bool SerialLink::setFlowType(int flow)
......
......@@ -208,8 +208,9 @@ Freenect::get3DPointCloudData(void)
{
if (data[i] > 0 && data[i] <= 2048)
{
// see www.ros.org/wiki/kinect_node for details
double range = 1.0f / (-0.00307f * static_cast<float>(data[i]) + 3.33f);
double range = baseline * depthCameraParameters.fx
/ (1.0 / 8.0 * (disparityOffset
- static_cast<double>(data[i])));
if (range > 0.0f)
{
......@@ -340,7 +341,10 @@ Freenect::readConfigFile(void)
settings.value("transform/R33").toDouble(),
settings.value("transform/Tz").toDouble(),
0.0, 0.0, 0.0, 1.0);
transformMatrix = transformMatrix.transposed();
transformMatrix = transformMatrix.inverted();
baseline = settings.value("transform/baseline").toDouble();
disparityOffset = settings.value("transform/disparity_offset").toDouble();
}
void
......
......@@ -119,6 +119,8 @@ private:
IntrinsicCameraParameters depthCameraParameters;
QMatrix4x4 transformMatrix;
double baseline;
double disparityOffset;
// tilt angle of Kinect camera
int tiltAngle;
......
......@@ -41,12 +41,12 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
mavlink_message_t* msg = &message;
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t* msg = &message;
if (message.sysid == uasId)
{
......@@ -168,5 +168,9 @@ void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int c
mavlink_message_t msg;
mavlink_msg_watchdog_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &payload);
sendMessage(msg);
#else
Q_UNUSED(watchdogId);
Q_UNUSED(processId);
Q_UNUSED(command);
#endif
}
......@@ -169,10 +169,16 @@ void SlugsMAV::emitSignals (void){
case 2:
emit slugsAirData(uasId, mlAirData);
emit slugsDiagnostic(uasId,mlDiagnosticData);
break;
case 3:
emit slugsPilotConsolePWM(uasId,mlPilotConsoleData);
emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(1,(mlPilotConsoleData.dla- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(2,(mlPilotConsoleData.dr- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(3,(mlPilotConsoleData.dra- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.dt- 1000.0f)/1000.0f);
emit slugsPWM(uasId, mlPwmCommands);
break;
......@@ -184,11 +190,13 @@ void SlugsMAV::emitSignals (void){
case 5:
emit slugsFilteredData(uasId,mlFilteredData);
emit slugsGPSDateTime(uasId, mlGpsDateTime);
break;
case 6:
emit slugsActionAck(uasId,mlActionAck);
emit emitGpsSignals();
break;
}
......@@ -212,20 +220,30 @@ void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){
if (mlGpsData.fix_type > 0){
qDebug()<<"After Emit GPS Signal"<<mlGpsData.fix_type;
//ToDo Uncomment if. it was comment only to test
// if (mlGpsData.fix_type > 0){
emit globalPositionChanged(this,
mlGpsData.lon,
mlGpsData.lat,
mlGpsData.alt,
0.0);
// Smaller than threshold and not NaN
if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
} else {
emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
}
}
emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);
// // Smaller than threshold and not NaN
// if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
// // emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
// }
// else {
// emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
// }
//}
}
void SlugsMAV::emitPidSignal()
......
......@@ -47,6 +47,7 @@ public slots:
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
void slugsGPSCogSog(int uasId, double cog, double sog);
#ifdef MAVLINK_ENABLED_SLUGS
......@@ -67,6 +68,8 @@ signals:
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif
protected:
......
......@@ -43,12 +43,16 @@ This file is part of the QGROUNDCONTROL project
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
#include "SerialLink.h"
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),
......@@ -93,6 +97,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
UAS::~UAS()
{
delete links;
links=NULL;
}
int UAS::getUASID() const
......@@ -124,6 +129,7 @@ void UAS::setSelected()
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
if (!link) return;
if (!links->contains(link))
{
addLink(link);
......@@ -149,8 +155,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (this->type != mavlink_msg_heartbeat_get_type(&message))
{
this->type = mavlink_msg_heartbeat_get_type(&message);
this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
emit systemTypeSet(this, type);
}
break;
case MAVLINK_MSG_ID_BOOT:
getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
......@@ -328,6 +336,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Vz", pos.vz, time);
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;
//emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
// Set internal state
if (!positionLock)
......@@ -363,11 +375,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
// Send to patch antenna
mavlink_message_t msg;
mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
sendMessage(msg);
//TODO fix this hack for forwarding of global position for patch antenna tracking
forwardMessage(message);
}
break;
case MAVLINK_MSG_ID_GPS_RAW:
......@@ -695,7 +704,12 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
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);
#endif
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
#endif
}
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
......@@ -704,6 +718,11 @@ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
mavlink_message_t msg;
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);
#endif
}
......@@ -819,8 +838,31 @@ void UAS::sendMessage(mavlink_message_t message)
}
}
void UAS::forwardMessage(mavlink_message_t message)
{
// Emit message on all links that are currently connected
QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
foreach(LinkInterface* link, link_list)
{
SerialLink* serial = dynamic_cast<SerialLink*>(link);
if(serial != 0)
{
for(int i=0;i<links->size();i++)
{
if(serial != links->at(i))
{
qDebug()<<"Forwarding Over link: "<<serial->getName()<<" "<<serial;
sendMessage(serial, message);
}
}
}
}
}
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
if(!link) return;
// Create buffer
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Write message into buffer, prepending start sign
......@@ -1490,7 +1532,7 @@ void UAS::addLink(LinkInterface* link)
links->append(link);
}
//links->append(link);
//qDebug() << " ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
qDebug() << link<<" ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
}
/**
......
......@@ -79,25 +79,26 @@ public:
/** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks();
double getLocalX() const { return localX; };
double getLocalY() const { return localY; };
double getLocalZ() const { return localZ; };
double getLatitude() const { return latitude; };
double getLongitude() const { return longitude; };
double getAltitude() const { return altitude; };
double getLocalX() const { return localX; }
double getLocalY() const { return localY; }
double getLocalZ() const { return localZ; }
double getLatitude() const { return latitude; }
double getLongitude() const { return longitude; }
double getAltitude() const { return altitude; }
double getRoll() const { return roll; };
double getPitch() const { return pitch; };
double getYaw() const { return yaw; };
double getRoll() const { return roll; }
double getPitch() const { return pitch; }
double getYaw() const { return yaw; }
friend class UASWaypointManager;
protected:
int uasId; ///< Unique system ID
int type; ///< UAS type (from type enum)
unsigned char type; ///< UAS type (from type enum)
quint64 startTime; ///< The time the UAS was switched on
CommStatus commStatus; ///< Communication status
QString name; ///< Human-friendly name of the vehicle, e.g. bravo
int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
......@@ -164,6 +165,8 @@ protected:
public:
UASWaypointManager &getWaypointManager(void) { return waypointManager; }
int getSystemType();
int getAutopilotType() {return autopilot;}
void setAutopilotType(int apType) { autopilot = apType;}
public slots:
/** @brief Launches the system **/
......@@ -215,6 +218,9 @@ public slots:
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void sendMessage(mavlink_message_t message);
/** @brief Temporary Hack for sending packets to patch Antenna. Send a message over all serial links except for this UAS's */
void forwardMessage(mavlink_message_t message);
/** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
void setSelected();
......
......@@ -157,6 +157,9 @@ public:
return color;
}
virtual int getAutopilotType() = 0;
virtual void setAutopilotType(int apType)= 0;
public slots:
/** @brief Launches the system/Liftof **/
......@@ -241,6 +244,8 @@ public slots:
virtual void startGyroscopeCalibration() = 0;
virtual void startPressureCalibration() = 0;
protected:
QColor color;
......
......@@ -85,6 +85,11 @@ void UASManager::addUAS(UASInterface* uas)
}
}
QList<UASInterface*> UASManager::getUASList()
{
return systems.values();
}
UASInterface* UASManager::getActiveUAS()
{
if(!activeUAS)
......@@ -96,6 +101,11 @@ UASInterface* UASManager::getActiveUAS()
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
UASInterface* UASManager::silentGetActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
bool UASManager::launchActiveUAS()
{
// If the active UAS is set, execute command
......
......@@ -57,6 +57,7 @@ public:
* @return NULL pointer if no UAS exists, active UAS else
**/
UASInterface* getActiveUAS();
UASInterface* silentGetActiveUAS();
/**
* @brief Get the UAS with this id
*
......@@ -68,6 +69,8 @@ public:
**/
UASInterface* getUASForId(int id);
QList<UASInterface*> getUASList();
public slots:
......
......@@ -47,6 +47,7 @@ This file is part of the QGROUNDCONTROL project
#endif
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
#include "LinkManager.h"
CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolInterface* protocol, QWidget *parent, Qt::WindowFlags flags) : QWidget(parent, flags)
{
......@@ -58,6 +59,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
// add link types
ui.linkType->addItem("Serial",QGC_LINK_SERIAL);
ui.linkType->addItem("UDP",QGC_LINK_UDP);
ui.linkType->addItem("Simulation",QGC_LINK_SIMULATION);
ui.linkType->addItem("Serial Forwarding",QGC_LINK_FORWARDING);
ui.connectionType->addItem("MAVLink", QGC_PROTOCOL_MAVLINK);
// Create action to open this menu
// Create configuration action for this link
......@@ -195,11 +200,20 @@ void CommConfigurationWindow::setLinkName(QString name)
void CommConfigurationWindow::remove()
{
link->disconnect();
//delete link;
//delete action;
if(action) delete action; //delete action first since it has a pointer to link
action=NULL;
if(link)
{
LinkManager::instance()->removeLink(link); //remove link from LinkManager list
link->disconnect(); //disconnect port, and also calls terminate() to stop the thread
if (link->isRunning()) link->terminate(); // terminate() the serial thread just in case it is still running
link->wait(); // wait() until thread is stoped before deleting
delete link;
}
link=NULL;
this->window()->close();
qDebug() << "TODO: Link cannot be deleted: CommConfigurationWindow::remove() NOT IMPLEMENTED!";
}
void CommConfigurationWindow::connectionState(bool connect)
......
......@@ -42,7 +42,14 @@ This file is part of the QGROUNDCONTROL project
enum qgc_link_t
{
QGC_LINK_SERIAL,
QGC_LINK_UDP
QGC_LINK_UDP,
QGC_LINK_SIMULATION,
QGC_LINK_FORWARDING
};
enum qgc_protocol_t
{
QGC_PROTOCOL_MAVLINK
};
#ifdef OPAL_RT
......
......@@ -43,23 +43,7 @@
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="linkType">
<item>
<property name="text">
<string>Serial Link</string>
</property>
</item>
<item>
<property name="text">
<string>UDP</string>
</property>
</item>
<item>
<property name="text">
<string>Simulation</string>
</property>
</item>
</widget>
<widget class="QComboBox" name="linkType"/>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_5">
......@@ -71,13 +55,8 @@
<item row="1" column="1">
<widget class="QComboBox" name="connectionType">
<property name="currentIndex">
<number>0</number>
<number>-1</number>
</property>
<item>
<property name="text">
<string>MAVLink</string>
</property>
</item>
</widget>
</item>
</layout>
......
......@@ -165,6 +165,19 @@ HUD::~HUD()
}
void HUD::showEvent(QShowEvent* event)
{
Q_UNUSED(event);
if (isVisible())
{
refreshTimer->start();
}
else
{
refreshTimer->stop();
}
}
void HUD::start()
{
refreshTimer->start();
......
......@@ -123,6 +123,8 @@ protected:
float refLineWidthToPen(float line);
/** @brief Rotate a polygon around a point clockwise */
void rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin);
/** @brief Override base class show */
virtual void showEvent(QShowEvent* event);
QImage* image; ///< Double buffer image
QImage glImage; ///< The background / camera image
......
This diff is collapsed.
......@@ -70,7 +70,7 @@ This file is part of the QGROUNDCONTROL project
#include "SlugsPIDControl.h"
#include "slugshilsim.h"
#include "SlugsHilSim.h"
#include "SlugsVideoCamControl.h"
......@@ -87,6 +87,9 @@ public:
~MainWindow();
public slots:
// /** @brief Store the mainwindow settings */
// void storeSettings();
/**
* @brief Shows a status message on the bottom status bar
*
......@@ -119,22 +122,8 @@ public slots:
void loadEngineerView();
/** @brief Load view for operator */
void loadOperatorView();
/** @brief Load 3D view */
void load3DView();
/** @brief Load 3D Google Earth view */
void loadGoogleEarthView();
/** @brief Load 3D map view */
void load3DMapView();
/** @brief Load view with all widgets */
void loadAllView();
/** @brief Load MAVLink XML generator view */
void loadMAVLinkView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/** @brief Load view for global operator, allowing to flight on earth */
void loadGlobalOperatorView();
/** @brief Show the online help for users */
void showHelp();
......@@ -143,21 +132,199 @@ public slots:
/** @brief Show the project roadmap */
void showRoadMap();
// Fixme find a nicer solution that scales to more AP types
void loadSlugsView();
void loadPixhawkView();
/** @brief Shows the widgets based on configuration and current view and autopilot */
void presentView();
/** @brief Reload the CSS style sheet */
void reloadStylesheet();
/*
==========================================================
Potentially Deprecated
==========================================================
*/
void loadPixhawkEngineerView();
/** @brief Load view with all widgets */
void loadAllView();
void loadWidgets();
/** @brief Load data view, allowing to plot flight data */
void loadDataView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/** @brief Load 3D map view */
void load3DMapView();
/** @brief Load 3D Google Earth view */
void loadGoogleEarthView();
/** @brief Load 3D view */
void load3DView();
/**
* @brief Shows a Docked Widget based on the action sender
*
* This slot is written to be used in conjunction with the addToToolsMenu function
* It shows the QDockedWidget based on the action sender
*
*/
void showToolWidget();
/**
* @brief Shows a Widget from the center stack based on the action sender
*
* This slot is written to be used in conjunction with the addToCentralWidgetsMenu function
* It shows the Widget based on the action sender
*
*/
void showCentralWidget();
/** @brief Updates a QDockWidget's checked status based on its visibility */
void updateVisibilitySettings (bool vis);
/** @brief Updates a QDockWidget's location */
void updateLocationSettings (Qt::DockWidgetArea location);
protected:
// These defines are used to save the settings when selecting with
// which widgets populate the views
// FIXME: DO NOT PUT CUSTOM VALUES IN THIS ENUM since it is iterated over
// this will be fixed in a future release.
typedef enum _TOOLS_WIDGET_NAMES {
MENU_UAS_CONTROL,
MENU_UAS_INFO,
MENU_CAMERA,
MENU_UAS_LIST,
MENU_WAYPOINTS,
MENU_STATUS,
MENU_DETECTION,
MENU_DEBUG_CONSOLE,
MENU_PARAMETERS,
MENU_HDD_1,
MENU_HDD_2,
MENU_WATCHDOG,
MENU_HUD,
MENU_HSI,
MENU_RC_VIEW,
MENU_SLUGS_DATA,
MENU_SLUGS_PID,
MENU_SLUGS_HIL,
MENU_SLUGS_CAMERA,
CENTRAL_SEPARATOR= 255, // do not change
CENTRAL_LINECHART,
CENTRAL_PROTOCOL,
CENTRAL_MAP,
CENTRAL_3D_LOCAL,
CENTRAL_3D_MAP,
CENTRAL_OSGEARTH,
CENTRAL_GOOGLE_EARTH,
CENTRAL_HUD,
CENTRAL_DATA_PLOT,
}TOOLS_WIDGET_NAMES;
typedef enum _SETTINGS_SECTIONS {
SECTION_MENU,
SUB_SECTION_CHECKED,
SUB_SECTION_LOCATION,
} SETTINGS_SECTIONS;
typedef enum _VIEW_SECTIONS {
VIEW_ENGINEER,
VIEW_OPERATOR,
VIEW_PILOT,
VIEW_MAVLINK,
} VIEW_SECTIONS;
QHash<int, QAction*> toolsMenuActions; // Holds ptr to the Menu Actions
QHash<int, QWidget*> dockWidgets; // Holds ptr to the Actual Dock widget
QHash<int, Qt::DockWidgetArea> dockWidgetLocations; // Holds the location
/**
* @brief Adds an already instantiated QDockedWidget to the Tools Menu
*
* This function does all the hosekeeping to have a QDockedWidget added to the
* tools menu and connects the QMenuAction to a slot that shows the widget and
* checks/unchecks the tools menu item
*
* @param widget The QDockedWidget being added
* @param title The entry that will appear in the Menu and in the QDockedWidget title bar
* @param slotName The slot to which the triggered() signal of the menu action will be connected.
* @param tool The ENUM defined in MainWindow.h that is associated to the widget
* @param location The default location for the QDockedWidget in case there is no previous key in the settings
*/
void addToToolsMenu (QWidget* widget, const QString title, const char * slotName, TOOLS_WIDGET_NAMES tool, Qt::DockWidgetArea location);
/**
* @brief Determines if a QDockWidget needs to be show and if so, shows it
*
* Based on the the autopilot and the current view it queries the settings and shows the
* widget if necessary
*
* @param widget The QDockWidget requested to be shown
* @param view The view for which the QDockWidget is requested
*/
void showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view = VIEW_MAVLINK);
/**
* @brief Adds an already instantiated QWidget to the center stack
*
* This function does all the hosekeeping to have a QWidget added to the tools menu
* tools menu and connects the QMenuAction to a slot that shows the widget and
* checks/unchecks the tools menu item. This is used for all the central widgets (those in
* the center stack.
*
* @param widget The QWidget being added
* @param title The entry that will appear in the Menu
* @param slotName The slot to which the triggered() signal of the menu action will be connected.
* @param centralWidget The ENUM defined in MainWindow.h that is associated to the widget
*/
void addToCentralWidgetsMenu ( QWidget* widget, const QString title,const char * slotName, TOOLS_WIDGET_NAMES centralWidget);
/**
* @brief Determines if a QWidget needs to be show and if so, shows it
*
* Based on the the autopilot and the current view it queries the settings and shows the
* widget if necessary
*
* @param centralWidget The QWidget requested to be shown
* @param view The view for which the QWidget is requested
*/
void showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view);
/** @brief Keeps track of the current view */
VIEW_SECTIONS currentView;
QStatusBar* statusBar;
QStatusBar* createStatusBar();
void loadWidgets();
void connectActions();
void clearView();
void buildWidgets();
void connectWidgets();
void arrangeCenterStack();
void buildCommonWidgets();
void buildPxWidgets();
void buildSlugsWidgets();
void connectCommonWidgets();
void connectPxWidgets();
void connectSlugsWidgets();
void arrangeCommonCenterStack();
void arrangePxCenterStack();
void arrangeSlugsCenterStack();
void connectCommonActions();
void connectPxActions();
void connectSlugsActions();
void configureWindowName();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
......@@ -168,9 +335,13 @@ protected:
LinkInterface* udpLink;
QSettings settings;
QStackedWidget *centerStack;
// Center widgets
QPointer<Linecharts> linechartWidget;
QPointer<HUD> hudWidget;
QPointer<MapWidget> mapWidget;
QPointer<XMLCommProtocolWidget> protocolWidget;
QPointer<QGCDataPlot2D> dataplotWidget;
......@@ -193,9 +364,12 @@ protected:
QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> hudDockWidget;
QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsPIDControlWidget;
QPointer<QDockWidget> slugsHilSimWidget;
......@@ -216,6 +390,7 @@ protected:
QAction* killUASAct;
QAction* simulateUASAct;
LogCompressor* comp;
QString screenFileName;
QTimer* videoTimer;
......@@ -223,6 +398,8 @@ protected:
private:
Ui::MainWindow ui;
QString buildMenuKey (SETTINGS_SECTIONS section , TOOLS_WIDGET_NAMES tool, VIEW_SECTIONS view);
};
#endif /* _MAINWINDOW_H_ */
......@@ -45,15 +45,30 @@
<property name="title">
<string>File</string>
</property>
<addaction name="actionJoystickSettings"/>
<addaction name="actionJoystick_Settings"/>
<addaction name="actionSimulate"/>
<addaction name="separator"/>
<addaction name="actionExit"/>
</widget>
<widget class="QMenu" name="menuNetwork">
<property name="title">
<string>Network</string>
</property>
<addaction name="actionAdd_Link"/>
<addaction name="separator"/>
</widget>
<widget class="QMenu" name="menuConnected_Systems">
<property name="title">
<string>Select System</string>
</property>
</widget>
<widget class="QMenu" name="menuUnmanned_System">
<property name="title">
<string>Unmanned System</string>
</property>
<property name="separatorsCollapsible">
<bool>false</bool>
</property>
<addaction name="actionLiftoff"/>
<addaction name="actionLand"/>
<addaction name="actionEmergency_Land"/>
......@@ -61,59 +76,39 @@
<addaction name="separator"/>
<addaction name="actionConfiguration"/>
</widget>
<widget class="QMenu" name="menuNetwork">
<property name="title">
<string>Network</string>
</property>
<addaction name="actionAdd_Link"/>
<addaction name="separator"/>
</widget>
<widget class="QMenu" name="menuWindow">
<widget class="QMenu" name="menuTools">
<property name="title">
<string>Window</string>
<string>Tools</string>
</property>
<addaction name="actionEngineerView"/>
<addaction name="actionPilotView"/>
<addaction name="actionOperatorView"/>
<addaction name="action3DMapView"/>
<addaction name="action3DView"/>
<addaction name="actionGoogleEarthView"/>
<addaction name="actionGlobalOperatorView"/>
<addaction name="separator"/>
<addaction name="actionShow_MAVLink_view"/>
<addaction name="actionShow_data_analysis_view"/>
<addaction name="actionShow_full_view"/>
<addaction name="actionStyleConfig"/>
<addaction name="actionShow_Slugs_View"/>
</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"/>
<addaction name="actionOnline_Documentation"/>
<addaction name="actionProject_Roadmap_2"/>
<addaction name="actionDeveloper_Credits"/>
</widget>
<widget class="QMenu" name="menuConnected_Systems">
<widget class="QMenu" name="menuPerspectives">
<property name="title">
<string>Select System</string>
<string>Perspectives</string>
</property>
<addaction name="actionOperatorsView"/>
<addaction name="actionEngineersView"/>
<addaction name="actionPilotsView"/>
<addaction name="separator"/>
<addaction name="actionMavlinkView"/>
<addaction name="actionReloadStyle"/>
</widget>
<addaction name="menuMGround"/>
<addaction name="menuNetwork"/>
<addaction name="menuConnected_Systems"/>
<addaction name="menuUnmanned_System"/>
<addaction name="menuWindow"/>
<addaction name="menuTools"/>
<addaction name="menuPerspectives"/>
<addaction name="menuHelp"/>
</widget>
<widget class="QToolBar" name="mainToolBar">
<attribute name="toolBarArea">
<enum>TopToolBarArea</enum>
</attribute>
<attribute name="toolBarBreak">
<bool>false</bool>
</attribute>
</widget>
<widget class="QStatusBar" name="statusBar"/>
<action name="actionExit">
<property name="icon">
......@@ -218,6 +213,9 @@
<property name="text">
<string>Joystick settings</string>
</property>
<property name="visible">
<bool>true</bool>
</property>
</action>
<action name="actionOperatorView">
<property name="icon">
......@@ -348,6 +346,90 @@
<string>Show Slugs View</string>
</property>
</action>
<action name="actionJoystick_Settings">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/input-gaming.svg</normaloff>:/images/devices/input-gaming.svg</iconset>
</property>
<property name="text">
<string>Joystick Settings</string>
</property>
<property name="visible">
<bool>false</bool>
</property>
</action>
<action name="actionOnline_Documentation">
<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>Online Documentation</string>
</property>
</action>
<action name="actionProject_Roadmap_2">
<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="actionDeveloper_Credits">
<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>Developer Credits</string>
</property>
</action>
<action name="actionOperatorsView">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/weather-overcast.svg</normaloff>:/images/status/weather-overcast.svg</iconset>
</property>
<property name="text">
<string>Operator</string>
</property>
</action>
<action name="actionEngineersView">
<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>Engineer</string>
</property>
</action>
<action name="actionMavlinkView">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/network-wired.svg</normaloff>:/images/devices/network-wired.svg</iconset>
</property>
<property name="text">
<string>Mavlink</string>
</property>
</action>
<action name="actionReloadStyle">
<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>Reload Style</string>
</property>
</action>
<action name="actionPilotsView">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/network-wireless-encrypted.svg</normaloff>:/images/status/network-wireless-encrypted.svg</iconset>
</property>
<property name="text">
<string>Pilot</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......@@ -372,3 +454,5 @@
</connection>
</connections>
</ui>
......@@ -562,6 +562,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// Icon
QPen* pointpen = new QPen(uasColor);
qDebug() << uas->getUASName();
MAV2DIcon* p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
geomLayer->addGeometry(p);
......@@ -592,21 +593,12 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
}
// points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen));
// points.append(new CirclePoint(8.270476, 50.021426, 15, "Wiesbaden-Mainz-Kastel, Ruthof", Point::Middle, pointpen));
// // "Blind" Points
// points.append(new Point(8.266445, 50.025913, "Wiesbaden-Mainz-Kastel, Mudra Kaserne"));
// points.append(new Point(8.260378, 50.030345, "Wiesbaden-Mainz-Amoneburg, Dyckerhoffstraße"));
// Connect click events of the layer to this object
// connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)),
// this, SLOT(geometryClicked(Geometry*, QPoint)));
// Sets the view to the interesting area
//QList<QPointF> view;
//view.append(QPointF(8.24764, 50.0319));
//view.append(QPointF(8.28412, 49.9998));
// mc->setView(view);
updatePosition(0, lat, lon);
}
}
......
......@@ -40,8 +40,6 @@ This file is part of the PIXHAWK project
#include <QDebug>
#include <QMap>
#include "MG.h"
ObjectDetectionView::ObjectDetectionView(QString folder, QWidget *parent) :
QWidget(parent),
patternList(),
......@@ -117,7 +115,7 @@ void ObjectDetectionView::newPattern(int uasId, QString patternPath, float confi
m_ui->listWidget->addItem(pattern.name + separator + "(" + QString::number(pattern.count) + ")" + separator + QString::number(pattern.confidence));
// load image
QString filePath = MG::DIR::getSupportFilesDirectory() + "/" + patternFolder + "/" + patternPath.split("/", QString::SkipEmptyParts).last();
QString filePath = patternFolder + "/" + patternPath.split("/", QString::SkipEmptyParts).last();
QPixmap image = QPixmap(filePath);
if (image.width() > image.height())
image = image.scaledToWidth(m_ui->imageLabel->width());
......
......@@ -51,6 +51,15 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
// Setup UI connections
connect(m_ui->vehicleComboBox, SIGNAL(activated(int)), this, SLOT(selectUAS(int)));
// Get current MAV list
QList<UASInterface*> systems = UASManager::instance()->getUASList();
// Add each of them
foreach (UASInterface* sys, systems)
{
addUAS(sys);
}
// Setup MAV connections
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
this->setVisible(false);
......
#include "QGCMainWindowAPConfigurator.h"
QGCMainWindowAPConfigurator::QGCMainWindowAPConfigurator(QObject *parent) :
QObject(parent)
{
}
#ifndef QGCMAINWINDOWAPCONFIGURATOR_H
#define QGCMAINWINDOWAPCONFIGURATOR_H
#include <QObject>
class QGCMainWindowAPConfigurator : public QObject
{
Q_OBJECT
public:
explicit QGCMainWindowAPConfigurator(QObject *parent = 0);
signals:
public slots:
};
#endif // QGCMAINWINDOWAPCONFIGURATOR_H
......@@ -115,10 +115,10 @@ void QGCRemoteControlView::setUASId(int id)
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
......
......@@ -52,6 +52,66 @@ RadioCalibrationWindow::RadioCalibrationWindow(QWidget *parent) :
setUASId(0);
}
void RadioCalibrationWindow::setChannelRaw(int ch, float raw)
{
/** this expects a particular channel to function mapping
\todo allow run-time channel mapping
*/
switch (ch)
{
case 0:
aileron->channelChanged(raw);
break;
case 1:
elevator->channelChanged(raw);
break;
case 2:
throttle->channelChanged(raw);
break;
case 3:
rudder->channelChanged(raw);
break;
case 4:
gyro->channelChanged(raw);
break;
case 5:
pitch->channelChanged(raw);
break;
}
}
void RadioCalibrationWindow::setChannelScaled(int ch, float normalized)
{
// /** this expects a particular channel to function mapping
// \todo allow run-time channel mapping
// */
// switch (ch)
// {
// case 0:
// aileron->channelChanged(raw);
// break;
// case 1:
// elevator->channelChanged(raw);
// break;
// case 2:
// throttle->channelChanged(raw);
// break;
// case 3:
// rudder->channelChanged(raw);
// break;
// case 4:
// gyro->channelChanged(raw);
// break;
// case 5:
// pitch->channelChanged(raw);
// break;
// }
}
void RadioCalibrationWindow::setChannel(int ch, float raw, float normalized)
{
/** this expects a particular channel to function mapping
......
......@@ -67,6 +67,8 @@ public:
public slots:
void setChannel(int ch, float raw, float normalized);
void setChannelRaw(int ch, float raw);
void setChannelScaled(int ch, float normalized);
void loadFile();
void saveFile();
void send();
......
......@@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project
#include <SerialConfigurationWindow.h>
#include <SerialLinkInterface.h>
#include <QDir>
#include <QSettings>
#include <QFileInfoList>
#ifdef _WIN32
#include <QextSerialEnumerator.h>
......@@ -509,12 +510,3 @@ void SerialConfigurationWindow::setLinkName(QString name)
setWindowTitle(tr("Configuration of ") + link->getName());
}
void SerialConfigurationWindow::remove()
{
link->disconnect();
//delete link;
//delete action;
this->window()->close();
qDebug() << "TODO: Link cannot be deleted: SerialConfigurationWindow::remove() NOT IMPLEMENTED!";
}
......@@ -60,12 +60,6 @@ public slots:
void setParityEven();
void setPortName(QString port);
void setLinkName(QString name);
/**
* @brief Remove this link
*
* Disconnects the associated link, removes it from all menus and closes the window.
*/
void remove();
void setupPortList();
protected slots:
......
......@@ -41,10 +41,12 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
connect(slugsMav, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugSpeedLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugAttitudeChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav,SIGNAL(slugsGPSCogSog(int,double,double)),this,SLOT(slugsGPSCogSog(int,double,double)));
//connect slugs especial messages
//connect slugs especial messages
connect(slugsMav, SIGNAL(slugsSensorBias(int,const mavlink_sensor_bias_t&)), this, SLOT(slugsSensorBiasChanged(int,const mavlink_sensor_bias_t&)));
connect(slugsMav, SIGNAL(slugsDiagnostic(int,const mavlink_diagnostic_t&)), this, SLOT(slugsDiagnosticMessageChanged(int,const mavlink_diagnostic_t&)));
connect(slugsMav, SIGNAL(slugsCPULoad(int,const mavlink_cpu_load_t&)), this, SLOT(slugsCpuLoadChanged(int,const mavlink_cpu_load_t&)));
......@@ -53,6 +55,8 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
connect(slugsMav, SIGNAL(slugsPWM(int,const mavlink_pwm_commands_t&)),this,SLOT(slugsPWMChanged(int,const mavlink_pwm_commands_t&)));
connect(slugsMav, SIGNAL(slugsFilteredData(int,const mavlink_filtered_data_t&)),this,SLOT(slugsFilteredDataChanged(int,const mavlink_filtered_data_t&)));
connect(slugsMav, SIGNAL(slugsGPSDateTime(int,const mavlink_gps_date_time_t&)),this,SLOT(slugsGPSDateTimeChanged(int,const mavlink_gps_date_time_t&)));
connect(slugsMav,SIGNAL(slugsAirData(int, const mavlink_air_data_t&)),this,SLOT(slugsAirDataChanged(int, const mavlink_air_data_t&)));
#endif // MAVLINK_ENABLED_SLUGS
// Set this UAS as active if it is the first one
......@@ -69,6 +73,15 @@ void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t
ui->m_Axr->setText(QString::number(rawData.xacc));
ui->m_Ayr->setText(QString::number(rawData.yacc));
ui->m_Azr->setText(QString::number(rawData.zacc));
ui->m_Mxr->setText(QString::number(rawData.xmag));
ui->m_Myr->setText(QString::number(rawData.ymag));
ui->m_Mzr->setText(QString::number(rawData.zmag));
ui->m_Gxr->setText(QString::number(rawData.xgyro));
ui->m_Gyr->setText(QString::number(rawData.ygyro));
ui->m_Gzr->setText(QString::number(rawData.zgyro));
}
void SlugsDataSensorView::setActiveUAS(UASInterface* uas){
......@@ -85,9 +98,13 @@ void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
Q_UNUSED(uas);
Q_UNUSED(time);
ui->m_GpsLatitude->setText(QString::number(lat));
ui->m_GpsLongitude->setText(QString::number(lon));
ui->m_GpsHeight->setText(QString::number(alt));
qDebug()<<"GPS Position = "<<lat<<" - "<<lon<<" - "<<alt;
}
......@@ -103,6 +120,8 @@ void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
ui->ed_y->setPlainText(QString::number(y));
ui->ed_z->setPlainText(QString::number(z));
//qDebug()<<"Local Position = "<<x<<" - "<<y<<" - "<<z;
}
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
......@@ -117,6 +136,9 @@ void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
ui->ed_vy->setPlainText(QString::number(vy));
ui->ed_vz->setPlainText(QString::number(vz));
//qDebug()<<"Speed Local Position = "<<vx<<" - "<<vy<<" - "<<vz;
}
void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
......@@ -132,6 +154,8 @@ void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
ui->m_Pitch->setPlainText(QString::number(slugpitch));
ui->m_Yaw->setPlainText(QString::number(slugyaw));
qDebug()<<"Attitude change = "<<slugroll<<" - "<<slugpitch<<" - "<<slugyaw;
}
......@@ -148,6 +172,7 @@ void SlugsDataSensorView::slugsSensorBiasChanged(int systemId,
}
void SlugsDataSensorView::slugsDiagnosticMessageChanged(int systemId,
const mavlink_diagnostic_t& diagnostic){
Q_UNUSED(systemId);
......@@ -229,17 +254,75 @@ void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
const mavlink_gps_date_time_t& gpsDateTime){
Q_UNUSED(systemId);
ui->m_GpsDate->setText(QString::number(gpsDateTime.month) + "/" +
QString::number(gpsDateTime.day) + "/" +
QString month, day;
month = QString::number(gpsDateTime.month);
day = QString::number(gpsDateTime.day);
if(gpsDateTime.month < 10) month = "0" + QString::number(gpsDateTime.month);
if(gpsDateTime.day < 10) day = "0" + QString::number(gpsDateTime.day);
ui->m_GpsDate->setText(day + "/" +
month + "/" +
QString::number(gpsDateTime.year));
ui->m_GpsTime->setText(QString::number(gpsDateTime.hour) + ":" +
QString::number(gpsDateTime.min) + ":" +
QString::number(gpsDateTime.sec));
QString hour, min, sec;
hour = QString::number(gpsDateTime.hour);
min = QString::number(gpsDateTime.min);
sec = QString::number(gpsDateTime.sec);
if(gpsDateTime.hour < 10) hour = "0" + QString::number(gpsDateTime.hour);
if(gpsDateTime.min < 10) min = "0" + QString::number(gpsDateTime.min);
if(gpsDateTime.sec < 10) sec = "0" + QString::number(gpsDateTime.sec);
ui->m_GpsTime->setText(hour + ":" +
min + ":" +
sec);
ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat));
}
/**
* @brief Updates the air data widget - 171
*/
void SlugsDataSensorView::slugsAirDataChanged(int systemId, const mavlink_air_data_t &airData)
{
Q_UNUSED(systemId);
ui->ed_dynamic->setText(QString::number(airData.dynamicPressure));
ui->ed_static->setText(QString::number(airData.staticPressure));
ui->ed_temp->setText(QString::number(airData.temperature));
// qDebug()<<"Air Data = "<<airData.dynamicPressure<<" - "
// <<airData.staticPressure<<" - "
// <<airData.temperature;
}
/**
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void SlugsDataSensorView::slugsGPSCogSog(int systemId,
double cog,
double sog)
{
Q_UNUSED(systemId);
ui->m_GpsCog->setText(QString::number(cog));
ui->m_GpsSog->setText(QString::number(sog));
}
#endif // MAVLINK_ENABLED_SLUGS
......@@ -70,6 +70,9 @@ public slots:
void setActiveUAS(UASInterface* uas);
/**
* @brief Updates the Raw Data widget
*/
void slugRawDataChanged (int uasId, const mavlink_raw_imu_t& rawData);
#ifdef MAVLINK_ENABLED_SLUGS
......@@ -114,58 +117,79 @@ public slots:
double lon,
double alt,
quint64 time);
/**
* @brief Updates the sensor bias widget
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void slugsGPSCogSog(int systemId,
double cog,
double sog);
/**
* @brief Updates the CPU load widget - 170
*/
void slugsCpuLoadChanged(int systemId,
const mavlink_cpu_load_t& cpuLoad);
/**
* @brief Updates the air data widget - 171
*/
void slugsAirDataChanged(int systemId,
const mavlink_air_data_t& airData);
/**
* @brief Updates the sensor bias widget - 172
*/
void slugsSensorBiasChanged(int systemId,
const mavlink_sensor_bias_t& sensorBias);
/**
* @brief Updates the diagnostic widget
* @brief Updates the diagnostic widget - 173
*/
void slugsDiagnosticMessageChanged(int systemId,
const mavlink_diagnostic_t& diagnostic);
/**
* @brief Updates the CPU load widget
*/
void slugsCpuLoadChanged(int systemId,
const mavlink_cpu_load_t& cpuLoad);
/**
* @brief Updates the Navigation widget
* @brief Updates the Navigation widget - 176
*/
void slugsNavegationChanged(int systemId,
const mavlink_slugs_navigation_t& slugsNavigation);
/**
* @brief Updates the Data Log widget
* @brief Updates the Data Log widget - 177
*/
void slugsDataLogChanged(int systemId,
const mavlink_data_log_t& dataLog);
/**
* @brief Updates the PWM Commands widget
* @brief Updates the PWM Commands widget - 175
*/
void slugsPWMChanged(int systemId,
const mavlink_pwm_commands_t& pwmCommands);
/**
* @brief Updates the filtered sensor measurements widget
* @brief Updates the filtered sensor measurements widget - 178
*/
void slugsFilteredDataChanged(int systemId,
const mavlink_filtered_data_t& filteredData);
/**
* @brief Updates the gps Date Time widget
* @brief Updates the gps Date Time widget - 179
*/
void slugsGPSDateTimeChanged(int systemId,
const mavlink_gps_date_time_t& gpsDateTime);
#endif // MAVLINK_ENABLED_SLUGS
protected:
......
......@@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>399</width>
<height>667</height>
<height>604</height>
</rect>
</property>
<property name="sizePolicy">
......@@ -24,18 +24,18 @@
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
<width>399</width>
<height>604</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
<layout class="QGridLayout" name="gridLayout_23">
<item row="0" column="0">
<widget class="QTabWidget" name="SlugsSensorView_tabWidget">
<property name="currentIndex">
<number>0</number>
<number>1</number>
</property>
<widget class="QWidget" name="tab">
<attribute name="title">
......@@ -989,7 +989,7 @@
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>13</height>
<height>5</height>
</size>
</property>
</spacer>
......@@ -1791,8 +1791,8 @@
<attribute name="title">
<string>Tab 2</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_11">
<item>
<layout class="QGridLayout" name="gridLayout_22">
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout_8">
<item>
<widget class="QGroupBox" name="gpsData_groupBox">
......@@ -4483,11 +4483,6 @@
</item>
</layout>
</widget>
<widget class="QWidget" name="tab_2">
<attribute name="title">
<string>Tab 4</string>
</attribute>
</widget>
</widget>
</item>
</layout>
......
......@@ -28,8 +28,8 @@ This file is part of the QGROUNDCONTROL project
*/
#include "slugshilsim.h"
#include "ui_slugshilsim.h"
#include "SlugsHilSim.h"
#include "ui_SlugsHilSim.h"
#include "LinkManager.h"
SlugsHilSim::SlugsHilSim(QWidget *parent) :
......
......@@ -55,6 +55,7 @@ void SlugsPIDControl::activeUasSet(UASInterface* uas)
connect(slugsMav,SIGNAL(slugsPidValues(int,mavlink_pid_t)),this, SLOT(receivePidValues(int,mavlink_pid_t)) );
connect(ui->setGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartSet()));
connect(ui->getGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartGet()));
}
#endif // MAVLINK_ENABLED_SLUG
......@@ -473,9 +474,9 @@ void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox()
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 8;
pidMessage.pVal = ui->dR_P_set->text().toFloat();
pidMessage.iVal = ui->dR_I_set->text().toFloat();
pidMessage.dVal = ui->dR_D_set->text().toFloat();
pidMessage.pVal = ui->P2dT_FF_set->text().toFloat();
pidMessage.iVal = 0;//ui->dR_I_set->text().toFloat();
pidMessage.dVal = 0;//ui->dR_D_set->text().toFloat();
mavlink_message_t msg;
......@@ -543,6 +544,7 @@ void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidVal
break;
case 8:
ui->P2dT_FF_get->setText(QString::number(pidValues.pVal));
break;
default:
......
......@@ -283,10 +283,10 @@ private:
#endif
QTimer* refreshTimerSet; ///< The main timer, controls the update view
QTimer* refreshTimerGet; ///< The main timer, controls the update view
QTimer* refreshTimerGet; ///< The main timer, controls the update view
int counterRefreshSet;
int counterRefreshGet;
QMutex valuesMutex;
QMutex valuesMutex;
};
#endif // SLUGSPIDCONTROL_H
......@@ -121,13 +121,6 @@
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="recepcion_label">
<property name="text">
<string>Recepcion</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_5">
<property name="orientation">
......@@ -956,6 +949,13 @@
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="recepcion_label">
<property name="text">
<string>Recepcion</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
......
This diff is collapsed.
......@@ -21,6 +21,9 @@ public slots:
void getDeltaPositionPad(int x, int y);
double getDistPixel(int x1, int y1, int x2, int y2);
QPointF ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2);
QPointF getPointBy_BearingDistance(double lat1, double lon1, double rumbo, double distancia);
signals:
void mouseMoveCoord(int x, int y);
......@@ -36,11 +39,17 @@ protected:
void mouseMoveEvent(QMouseEvent* event);
void paintEvent(QPaintEvent *pe);
private:
Ui::SlugsPadCameraControl *ui;
bool dragging;
int x1;
int y1;
int xFin;
int yFin;
double bearingPad;
double distancePad;
QString directionPad;
};
......
This diff is collapsed.
......@@ -27,22 +27,43 @@ public:
~SlugsVideoCamControl();
public slots:
/**
* @brief status = true: emit signal to draw a border cam over the map
*/
void changeViewCamBorderAtMapStatus(bool status);
void getDeltaPositionPad(double dir, double dist, QString dirText);
void mousePadPressEvent(int x, int y);
void mousePadReleaseEvent(int x, int y);
void mousePadMoveEvent(int x, int y);
/**
* @brief show the values of mousepad on ui (labels) and emit a changeCamPosition(signal)
* with values:
* bearing and distance from mouse over the pad
* dirText: direction of mouse movement in text format (up, right,right up,right down,
* left, left up, left down, down)
*/
void getDeltaPositionPad(double bearing, double distance, QString dirText);
// /**
// * @brief
// */
// void mousePadPressEvent(int x, int y);
// void mousePadReleaseEvent(int x, int y);
// void mousePadMoveEvent(int x, int y);
signals:
void changeCamPosition(double dist, double dir, QString textDir);
/**
* @brief emit values from mousepad:
* bearing and distance from mouse over the pad
* dirText: direction of mouse movement in text format (up, right,right up,right down,
* left, left up, left down, down)
*/
void changeCamPosition(double distance, double bearing, QString textDir);
/**
* @brief emit signal to draw a border cam over the map if status is true
*/
void viewCamBorderAtMap(bool status);
protected:
void mousePressEvent(QMouseEvent* event);
void mouseReleaseEvent(QMouseEvent* event);
void mouseMoveEvent(QMouseEvent* event);
// void mousePressEvent(QMouseEvent* event);
// void mouseReleaseEvent(QMouseEvent* event);
// void mouseMoveEvent(QMouseEvent* event);
......
......@@ -153,7 +153,7 @@ void WaypointList::loadWaypoints()
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
uas->getWaypointManager().loadWaypoints(fileName);
}
}
}
void WaypointList::transmit()
......@@ -474,14 +474,14 @@ void WaypointList::on_clearWPListButton_clicked()
if (uas)
{
emit clearPathclicked();
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
}
else
{
// if(isGlobalWP)
......
......@@ -146,6 +146,7 @@ void WaypointView::changedAction(int index)
break;
case MAV_ACTION_NAVIGATE:
m_ui->autoContinue->show();
m_ui->orbitSpinBox->show();
break;
case MAV_ACTION_LOITER:
m_ui->orbitSpinBox->show();
......
This diff is collapsed.
......@@ -56,7 +56,7 @@ maxInterval(MAX_STORAGE_INTERVAL),
timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds
automaticScrollActive(false),
m_active(true),
m_groundTime(false),
m_groundTime(true),
d_data(NULL),
d_curve(NULL)
{
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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