Commit 3e34eaab authored by Mariano Lizarraga's avatar Mariano Lizarraga

Merge branch 'experimental' of git@github.com:pixhawk/qgroundcontrol into experimental

parents 02f52d6b 6e2cba1b
......@@ -153,7 +153,7 @@ namespace qmapcontrol
QBuffer buffer(&bytes);
buffer.open(QIODevice::WriteOnly);
tileData.save(&buffer, "PNG");
// FIXME This is weird - why first write in buffer and then in file?
file.write(bytes);
file.close();
return true;
......
......@@ -39,10 +39,10 @@ namespace qmapcontrol
delete mapAdapter;
}
void Layer::setSize(QSize size)
void Layer::setSize(QSize size, QPoint screenmiddle)
{
this->size = size;
screenmiddle = QPoint(size.width()/2, size.height()/2);
this->screenmiddle = screenmiddle;// QPoint(size.width()/2, size.height()/2);
//QMatrix mat;
//mat.translate(480/2, 640/2);
//mat.rotate(45);
......@@ -292,10 +292,12 @@ namespace qmapcontrol
// PREFETCHING
int upper = mapmiddle_tile_y-tiles_above-1;
int right = mapmiddle_tile_x+tiles_right+1;
int left = mapmiddle_tile_x-tiles_right-1;
int lower = mapmiddle_tile_y+tiles_bottom+1;
// FIXME Make prefetching a parameter
int upper = mapmiddle_tile_y-tiles_above-2;
int right = mapmiddle_tile_x+tiles_right+2;
int left = mapmiddle_tile_x-tiles_right-2;
int lower = mapmiddle_tile_y+tiles_bottom+2;
int j = upper;
for (int i=left; i<=right; i++)
......
......@@ -139,7 +139,7 @@ namespace qmapcontrol
void moveWidgets(const QPoint mapmiddle_px) const;
void drawYourImage(QPainter* painter, const QPoint mapmiddle_px) const;
void drawYourGeometries(QPainter* painter, const QPoint mapmiddle_px, QRect viewport) const;
void setSize(QSize size);
void setSize(QSize size, QPoint screenmiddle);
QRect offscreenViewport() const;
bool takesMouseEvents() const;
void mouseEvent(const QMouseEvent*, const QPoint mapmiddle_px);
......
......@@ -47,6 +47,7 @@ namespace qmapcontrol
offFactor = factor;
composedOffscreenImage = QPixmap(offSize);
composedOffscreenImage2 = QPixmap(offSize);
resize(size);
}
float LayerManager::offscreenImageFactor()
......@@ -219,7 +220,7 @@ namespace qmapcontrol
{
mylayers.append(layer);
layer->setSize(size);
layer->setSize(size, screenmiddle);
connect(layer, SIGNAL(updateRequest(QRectF)),
this, SLOT(updateRequest(QRectF)));
......@@ -438,6 +439,20 @@ namespace qmapcontrol
forceRedraw();
}
void LayerManager::drawGeoms()
{
QPainter painter(&composedOffscreenImage);
QListIterator<Layer*> it(mylayers);
while (it.hasNext())
{
Layer* l = it.next();
if (l->layertype() == Layer::GeometryLayer && l->isVisible())
{
l->drawYourGeometries(&painter, mapmiddle_px, layer()->offscreenViewport());
}
}
}
void LayerManager::drawGeoms(QPainter* painter)
{
QListIterator<Layer*> it(mylayers);
......@@ -450,6 +465,8 @@ namespace qmapcontrol
}
}
}
void LayerManager::drawImage(QPainter* painter)
{
painter->drawPixmap(-scroll.x()-screenmiddle.x(),
......@@ -477,7 +494,7 @@ namespace qmapcontrol
while (it.hasNext())
{
Layer* l = it.next();
l->setSize(newSize);
l->setSize(newSize, screenmiddle);
}
newOffscreenImage();
......
......@@ -171,6 +171,8 @@ namespace qmapcontrol
*/
int currentZoom() const;
void drawGeoms();
void drawGeoms(QPainter* painter);
void drawImage(QPainter* painter);
......
......@@ -350,6 +350,12 @@ namespace qmapcontrol
{
update(rect);
}
void MapControl::drawGeometries()
{
layermanager->drawGeoms();
}
void MapControl::updateRequestNew()
{
// qDebug() << "MapControl::updateRequestNew()";
......
......@@ -345,6 +345,8 @@ namespace qmapcontrol
*/
void updateRequest ( QRect rect );
void drawGeometries();
//! updates the hole map by creating a new offscreen image
/*!
*
......
......@@ -261,7 +261,9 @@ HEADERS += src/MG.h \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCActionButton.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/QGCMAVLinkLogPlayer.h
src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|win32-msvc2008: {
......@@ -383,7 +385,9 @@ SOURCES += src/main.cc \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCActionButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/QGCMAVLinkLogPlayer.cc
src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc
macx|win32-msvc2008: {
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
......@@ -66,10 +66,13 @@ LinkManager::~LinkManager()
void LinkManager::add(LinkInterface* link)
{
if(!link) return;
connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
links.append(link);
emit newLink(link);
if (!links.contains(link))
{
if(!link) return;
connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
links.append(link);
emit newLink(link);
}
}
void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
......@@ -77,9 +80,18 @@ 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);
QList<LinkInterface*> linkList = protocolLinks.values(protocol);
// If protocol has not been added before (list length == 0)
// OR if link has not been added to protocol, add
if ((linkList.length() > 0 && !linkList.contains(link)) || linkList.length() == 0)
{
// Protocol is new, add
connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray)));
// Store the connection information in the protocol links map
protocolLinks.insertMulti(protocol, link);
}
//qDebug() << __FILE__ << __LINE__ << "ADDED LINK TO PROTOCOL" << link->getName() << protocol->getName() << "NEW SIZE OF LINK LIST:" << protocolLinks.size();
}
......
......@@ -40,9 +40,9 @@ This file is part of the QGROUNDCONTROL project
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h"
// MAVLINK includes
#include <QGCMAVLink.h>
#include "QGCMAVLink.h"
#include "QGC.h"
#include "MAVLinkSimulationMAV.h"
/**
* Create a simulated link. This link is connected to an input and output file.
......@@ -90,15 +90,13 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
this->name = "MAVLink simulation link";
}
// Initialize the pseudo-random number generator
srand(QTime::currentTime().msec());
maxTimeNoise = 0;
this->id = getNextLinkId();
LinkManager::instance()->add(this);
// Open packet log
mavlinkLogFile = new QFile();
//mavlinkLogFile->open(QIODevice::ReadOnly);
}
MAVLinkSimulationLink::~MAVLinkSimulationLink()
......@@ -118,6 +116,8 @@ void MAVLinkSimulationLink::run()
status.motor_block = 1;
status.packet_drop = 0;
forever
{
......@@ -146,6 +146,23 @@ void MAVLinkSimulationLink::run()
}
}
void MAVLinkSimulationLink::sendMAVLinkMessage(const mavlink_message_t* msg)
{
// Allocate buffer with packet data
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
unsigned int bufferlength = mavlink_msg_to_send_buffer(buf, msg);
// Pack to link buffer
readyBufferMutex.lock();
for (unsigned int i = 0; i < bufferlength; i++)
{
readyBuffer.enqueue(*(buf + i));
}
readyBufferMutex.unlock();
//qDebug() << "SENT MAVLINK MESSAGE FROM SYSTEM" << msg->sysid << "COMP" << msg->compid;
}
void MAVLinkSimulationLink::enqueue(uint8_t* stream, uint8_t* index, mavlink_message_t* msg)
{
// Allocate buffer with packet data
......@@ -162,10 +179,7 @@ void MAVLinkSimulationLink::mainloop()
// Test for encoding / decoding packets
// Test data stream
const int streamlength = 4096;
int streampointer = 0;
//const int testoffset = 0;
uint8_t stream[streamlength] = {};
streampointer = 0;
// Fake system values
......@@ -673,7 +687,7 @@ void MAVLinkSimulationLink::mainloop()
}*/
readyBufferMutex.lock();
for (int i = 0; i < streampointer; i++)
for (unsigned int i = 0; i < streampointer; i++)
{
readyBuffer.enqueue(*(stream + i));
}
......@@ -717,6 +731,8 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
if (mavlink_parse_char(this->id, data[i], &msg, &comm))
{
// MESSAGE RECEIVED!
qDebug() << "SIMULATION LINK RECEIVED MESSAGE!";
emit messageReceived(msg);
switch (msg.msgid)
{
......@@ -937,6 +953,8 @@ bool MAVLinkSimulationLink::connect()
emit connected(true);
start(LowPriority);
MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1);
Q_UNUSED(mav1);
// timer->start(rate);
return true;
}
......
......@@ -89,6 +89,7 @@ public slots:
virtual void mainloop();
bool connectLink(bool connect);
void connectLink();
void sendMAVLinkMessage(const mavlink_message_t* msg);
protected:
......@@ -106,7 +107,7 @@ protected:
QString simulationHeader;
/** File where the commands sent by the groundstation are stored **/
QFile* receiveFile;
QTextStream stream;
QTextStream textStream;
QTextStream* fileStream;
QTextStream* outStream;
/** Buffer which can be read from connected protocols through readBytes(). **/
......@@ -115,6 +116,10 @@ protected:
quint64 rate;
int maxTimeNoise;
quint64 lastSent;
static const int streamlength = 4096;
unsigned int streampointer;
//const int testoffset = 0;
uint8_t stream[streamlength];
int readyBytes;
QQueue<uint8_t> readyBuffer;
......@@ -133,6 +138,7 @@ protected:
signals:
void valueChanged(int uasId, QString curve, double value, quint64 usec);
void messageReceived(const mavlink_message_t& message);
};
......
#include <QDebug>
#include "MAVLinkSimulationMAV.h"
MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid) :
QObject(parent),
link(parent),
planner(parent, systemid),
systemid(systemid)
{
connect(&mainloopTimer, SIGNAL(timeout()), this, SLOT(mainloop()));
mainloopTimer.start(1000);
connect(link, SIGNAL(messageReceived(mavlink_message_t)), this, SLOT(handleMessage(mavlink_message_t)));
mainloop();
}
void MAVLinkSimulationMAV::mainloop()
{
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_SLUGS);
link->sendMAVLinkMessage(&msg);
}
void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
{
qDebug() << "MAV:" << systemid << "RECEIVED MESSAGE FROM" << msg.sysid << "COMP" << msg.compid;
switch(msg.msgid)
{
case MAVLINK_MSG_ID_ATTITUDE:
break;
}
}
#ifndef MAVLINKSIMULATIONMAV_H
#define MAVLINKSIMULATIONMAV_H
#include <QObject>
#include <QTimer>
#include "MAVLinkSimulationLink.h"
#include "MAVLinkSimulationWaypointPlanner.h"
class MAVLinkSimulationMAV : public QObject
{
Q_OBJECT
public:
explicit MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid);
signals:
public slots:
void mainloop();
void handleMessage(const mavlink_message_t& msg);
protected:
MAVLinkSimulationLink* link;
MAVLinkSimulationWaypointPlanner planner;
int systemid;
QTimer mainloopTimer;
};
#endif // MAVLINKSIMULATIONMAV_H
This diff is collapsed.
#ifndef MAVLINKSIMULATIONWAYPOINTPLANNER_H
#define MAVLINKSIMULATIONWAYPOINTPLANNER_H
#include <QObject>
#include <vector>
#include "MAVLinkSimulationLink.h"
#include "QGCMAVLink.h"
enum PX_WAYPOINTPLANNER_STATES
{
PX_WPP_IDLE = 0,
PX_WPP_SENDLIST,
PX_WPP_SENDLIST_SENDWPS,
PX_WPP_GETLIST,
PX_WPP_GETLIST_GETWPS,
PX_WPP_GETLIST_GOTALL
};
class MAVLinkSimulationWaypointPlanner : public QObject
{
Q_OBJECT
public:
explicit MAVLinkSimulationWaypointPlanner(MAVLinkSimulationLink *parent, int systemid);
signals:
public slots:
void handleMessage(const mavlink_message_t& msg);
protected:
MAVLinkSimulationLink* link;
bool idle; ///< indicates if the system is following the waypoints or is waiting
uint16_t current_active_wp_id; ///< id of current waypoint
bool yawReached; ///< boolean for yaw attitude reached
bool posReached; ///< boolean for position reached
uint64_t timestamp_lastoutside_orbit;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
uint64_t timestamp_firstinside_orbit;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
std::vector<mavlink_waypoint_t*> waypoints1; ///< vector1 that holds the waypoints
std::vector<mavlink_waypoint_t*> waypoints2; ///< vector2 that holds the waypoints
std::vector<mavlink_waypoint_t*>* waypoints; ///< pointer to the currently active waypoint vector
std::vector<mavlink_waypoint_t*>* waypoints_receive_buffer; ///< pointer to the receive buffer waypoint vector
PX_WAYPOINTPLANNER_STATES current_state;
uint16_t protocol_current_wp_id;
uint16_t protocol_current_count;
uint8_t protocol_current_partner_systemid;
uint8_t protocol_current_partner_compid;
uint64_t protocol_timestamp_lastaction;
unsigned int protocol_timeout;
uint64_t timestamp_last_send_setpoint;
uint8_t systemid;
uint8_t compid;
unsigned int setpointDelay;
float yawTolerance;
bool verbose;
bool debug;
bool silent;
void send_waypoint_ack(uint8_t target_systemid, uint8_t target_compid, uint8_t type);
void send_waypoint_current(uint16_t seq);
void send_setpoint(uint16_t seq);
void send_waypoint_count(uint8_t target_systemid, uint8_t target_compid, uint16_t count);
void send_waypoint(uint8_t target_systemid, uint8_t target_compid, uint16_t seq);
void send_waypoint_request(uint8_t target_systemid, uint8_t target_compid, uint16_t seq);
void send_waypoint_reached(uint16_t seq);
float distanceToSegment(uint16_t seq, float x, float y, float z);
float distanceToPoint(uint16_t seq, float x, float y, float z);
void mavlink_handler(const mavlink_message_t* msg);
};
#endif // MAVLINKSIMULATIONWAYPOINTPLANNER_H
This diff is collapsed.
......@@ -36,7 +36,9 @@ class SlugsMAV : public UAS
public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pwm_commands_t* getPwmCommands();
#endif
public slots:
/** @brief Receive a MAVLink message from this MAV */
......
......@@ -271,6 +271,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
GAudioOutput::instance()->stopEmergency();
GAudioOutput::instance()->say(audiostring);
}
if (state.status == MAV_STATE_POWEROFF)
{
emit systemRemoved(this);
emit systemRemoved();
}
}
break;
case MAVLINK_MSG_ID_RAW_IMU:
......
......@@ -262,6 +262,9 @@ signals:
* @param description longer textual description. Should be however limited to a short text, e.g. 200 chars.
*/
void statusChanged(UASInterface* uas, QString status, QString description);
/** @brief System has been removed / disconnected / shutdown cleanly, remove */
void systemRemoved(UASInterface* uas);
void systemRemoved();
/**
* @brief Received a plain text message from the robot
* This signal should NOT be used for standard communication, but rather for VERY IMPORTANT
......
......@@ -68,6 +68,8 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
// Create configuration action for this link
// Connect the current UAS
action = new QAction(QIcon(":/images/devices/network-wireless.svg"), "", link);
LinkManager::instance()->add(link);
action->setData(LinkManager::instance()->getLinks().indexOf(link));
setLinkName(link->getName());
connect(action, SIGNAL(triggered()), this, SLOT(show()));
......@@ -209,11 +211,12 @@ void CommConfigurationWindow::remove()
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->deleteLater();
}
link=NULL;
this->window()->close();
this->deleteLater();
}
void CommConfigurationWindow::connectionState(bool connect)
......
......@@ -402,17 +402,17 @@ void MainWindow::buildPxWidgets()
#ifdef QGC_OSG_ENABLED
if (!_3DWidget)
{
_3DWidget = Q3DWidgetFactory::get("PIXHAWK");
addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
// _3DWidget = Q3DWidgetFactory::get("PIXHAWK");
// addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
}
#endif
#ifdef QGC_OSGEARTH_ENABLED
if (!_3DMapWidget)
{
_3DMapWidget = Q3DWidgetFactory::get("MAP3D");
addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
}
// if (!_3DMapWidget)
// {
// _3DMapWidget = Q3DWidgetFactory::get("MAP3D");
// addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
// }
#endif
#if (defined _MSC_VER) | (defined Q_OS_MAC)
......@@ -1220,18 +1220,27 @@ void MainWindow::addLink()
SerialLink* link = new SerialLink();
// TODO This should be only done in the dialog itself
LinkManager::instance()->add(link);
LinkManager::instance()->addProtocol(link, mavlink);
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
// Go fishing for this link's configuration window
QList<QAction*> actions = ui.menuNetwork->actions();
ui.menuNetwork->addAction(commWidget->getAction());
commWidget->show();
foreach (QAction* act, actions)
{
if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(link))
{
act->trigger();
break;
}
}
}
void MainWindow::addLink(LinkInterface *link)
{
LinkManager::instance()->add(link);
LinkManager::instance()->addProtocol(link, mavlink);
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
ui.menuNetwork->addAction(commWidget->getAction());
......@@ -1290,7 +1299,11 @@ void MainWindow::UASCreated(UASInterface* uas)
break;
}
ui.menuConnected_Systems->addAction(icon, tr("Select %1 for control").arg(uas->getUASName()), uas, SLOT(setSelected()));
QAction* uasAction = new QAction(icon, tr("Select %1 for control").arg(uas->getUASName()), ui.menuConnected_Systems);
connect(uas, SIGNAL(systemRemoved()), uasAction, SLOT(deleteLater()));
connect(uasAction, SIGNAL(triggered()), uas, SLOT(setSelected()));
ui.menuConnected_Systems->addAction(uasAction);
// FIXME Should be not inside the mainwindow
if (debugConsoleDockWidget)
......
......@@ -42,14 +42,6 @@ MapWidget::MapWidget(QWidget *parent) :
QString buttonStyle("QAbstractButton { background-color: rgba(20, 20, 20, 45%); border-color: rgba(10, 10, 10, 50%)} QDoubleSpinBox { background-color: rgba(20, 20, 20, 45%); border-color: rgba(10, 10, 10, 50%)}");
mc->setPen(QGC::colorCyan.darker(400));
waypointIsDrag = false;
// Accept focus by clicking or keyboard
......@@ -267,6 +259,10 @@ MapWidget::MapWidget(QWidget *parent) :
drawCamBorder = false;
radioCamera = 10;
// mc->setZoom(20);
// //mc->resize(QSize(7025, 4968));
// mc->resize(QSize(3000, 2000));
//mc->setOffscreenImageFactor(15);
}
......@@ -650,6 +646,10 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, ""));
}
mc->drawGeometries();
//mc->updateRequest(QRect(QPoint(0, 0), QPoint(600, 600)));
//mc->updateRequestNew();//(uasTrails.value(uas->getUASID())->boundingBox().toRect());
......
......@@ -260,9 +260,9 @@ userConfigured(false)
connect(ui.portName, SIGNAL(currentIndexChanged(QString)), this, SLOT(setPortName(QString)));
connect(ui.baudRate, SIGNAL(activated(int)), this->link, SLOT(setBaudRateType(int)));
connect(ui.flowControlCheckBox, SIGNAL(toggled(bool)), this, SLOT(enableFlowControl(bool)));
connect(ui.parNone, SIGNAL(toggled(bool)), this, SLOT(setParityNone()));
connect(ui.parOdd, SIGNAL(toggled(bool)), this, SLOT(setParityOdd()));
connect(ui.parEven, SIGNAL(toggled(bool)), this, SLOT(setParityEven()));
connect(ui.parNone, SIGNAL(toggled(bool)), this, SLOT(setParityNone(bool)));
connect(ui.parOdd, SIGNAL(toggled(bool)), this, SLOT(setParityOdd(bool)));
connect(ui.parEven, SIGNAL(toggled(bool)), this, SLOT(setParityEven(bool)));
connect(ui.dataBitsSpinBox, SIGNAL(valueChanged(int)), this->link, SLOT(setDataBits(int)));
connect(ui.stopBitsSpinBox, SIGNAL(valueChanged(int)), this->link, SLOT(setStopBits(int)));
......@@ -283,7 +283,7 @@ userConfigured(false)
break;
default:
// Enforce default: no parity in link
setParityNone();
setParityNone(true);
ui.parNone->setChecked(true);
break;
}
......@@ -320,7 +320,8 @@ userConfigured(false)
}
}
SerialConfigurationWindow::~SerialConfigurationWindow() {
SerialConfigurationWindow::~SerialConfigurationWindow()
{
}
......@@ -472,19 +473,19 @@ void SerialConfigurationWindow::enableFlowControl(bool flow)
}
}
void SerialConfigurationWindow::setParityNone()
void SerialConfigurationWindow::setParityNone(bool accept)
{
link->setParityType(0);
if (accept) link->setParityType(0);
}
void SerialConfigurationWindow::setParityOdd()
void SerialConfigurationWindow::setParityOdd(bool accept)
{
link->setParityType(1);
if (accept) link->setParityType(1);
}
void SerialConfigurationWindow::setParityEven()
void SerialConfigurationWindow::setParityEven(bool accept)
{
link->setParityType(2);
if (accept) link->setParityType(2);
}
void SerialConfigurationWindow::setPortName(QString port)
......
......@@ -55,9 +55,9 @@ public:
public slots:
void configureCommunication();
void enableFlowControl(bool flow);
void setParityNone();
void setParityOdd();
void setParityEven();
void setParityNone(bool accept);
void setParityOdd(bool accept);
void setParityEven(bool accept);
void setPortName(QString port);
void setLinkName(QString name);
void setupPortList();
......
......@@ -51,12 +51,14 @@ SlugsHilSim::SlugsHilSim(QWidget *parent) :
linksAvailable.clear();
#ifdef MAVLINK_ENABLED_SLUGS
memset(&tmpAirData, 0, sizeof(mavlink_air_data_t));
memset(&tmpAttitudeData, 0, sizeof(mavlink_attitude_t));
memset(&tmpGpsData, 0, sizeof(mavlink_gps_raw_t));
memset(&tmpGpsTime, 0, sizeof(mavlink_gps_date_time_t));
memset(&tmpLocalPositionData, 0, sizeof(mavlink_sensor_bias_t));
memset(&tmpRawImuData, 0, sizeof(mavlink_raw_imu_t));
#endif
foreach (LinkInterface* link, LinkManager::instance()->getLinks())
{
......@@ -263,6 +265,7 @@ void SlugsHilSim::linkSelected(int cbIndex){
void SlugsHilSim::sendMessageToSlugs()
{
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_message_t msg;
mavlink_msg_local_position_encode(MG::SYSTEM::ID,
......@@ -306,11 +309,13 @@ void SlugsHilSim::sendMessageToSlugs()
&tmpGpsTime);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
#endif
}
void SlugsHilSim::commandDatagramToSimulink()
{
#ifdef MAVLINK_ENABLED_SLUGS
//mavlink_pwm_commands_t* pwdC = (static_cast<SlugsMAV*>(activeUas))->getPwmCommands();
mavlink_pwm_commands_t* pwdC;
......@@ -335,6 +340,7 @@ void SlugsHilSim::commandDatagramToSimulink()
setUInt16ToDatagram(data, &i, 11);//value default
txSocket->writeDatagram(data, QHostAddress::Broadcast, ui->ed_txPort->text().toInt());
#endif
}
void SlugsHilSim::setUInt16ToDatagram(QByteArray& datagram, unsigned char* pos, uint16_t value)
......
......@@ -69,9 +69,13 @@ protected:
mavlink_local_position_t tmpLocalPositionData;
mavlink_attitude_t tmpAttitudeData;
mavlink_raw_imu_t tmpRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_air_data_t tmpAirData;
#endif
mavlink_gps_raw_t tmpGpsData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_date_time_t tmpGpsTime;
#endif
public slots:
......@@ -150,4 +154,4 @@ private:
};
#endif // SLUGSHILSIM_H
#endif // SLUGSHILSIM_H
\ No newline at end of file
......@@ -181,7 +181,31 @@ QProgressBar::chunk#speedBar {
QProgressBar::chunk#thrustBar {
background-color: orange;
}</string>
}
QToolTip {
background-color: #090909;
border: 1px solid #379AC3;
border-radius: 3px;
color: #DDDDDF;
}
QMenu {
border: 1px solid #379AC3;
background-color: #050508;
color: #DDDDDF;
background-clip: border;
font-size: 11px;
}
QMenu::separator {
height: 1px;
background: #379AC3;
margin-top: 8px;
margin-bottom: 4px;
margin-left: 5px;
margin-right: 5px;
}</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
......
......@@ -28,7 +28,17 @@ QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent) :
if (dock)
{
dock->setWindowTitle(title);
dock->setObjectName(title+"DOCK");
}
// Try with parent
dock = dynamic_cast<QDockWidget*>(this->parentWidget());
if (dock)
{
dock->setWindowTitle(title);
dock->setObjectName(title+"DOCK");
}
this->setWindowTitle(title);
QList<UASInterface*> systems = UASManager::instance()->getUASList();
......
......@@ -31,6 +31,7 @@ This file is part of the PIXHAWK project
#include <cmath>
#include <QDateTime>
#include <QDebug>
#include <QMenu>
#include "QGC.h"
#include "MG.h"
......@@ -42,6 +43,8 @@ This file is part of the PIXHAWK project
UASView::UASView(UASInterface* uas, QWidget *parent) :
QWidget(parent),
startTime(0),
lastHeartbeat(0),
iconIsRed(true),
timeRemaining(0),
chargeLevel(0),
uas(uas),
......@@ -60,6 +63,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
alt(0),
groundDistance(0),
localFrame(false),
removeAction(new QAction("Remove this system", this)),
m_ui(new Ui::UASView)
{
m_ui->setupUi(this);
......@@ -92,6 +96,10 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL()));
connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));
// Allow to delete this widget
connect(removeAction, SIGNAL(triggered()), this, SLOT(deleteLater()));
connect(uas, SIGNAL(systemRemoved()), this, SLOT(deleteLater()));
// Set static values
......@@ -230,12 +238,11 @@ void UASView::hideEvent(QHideEvent* event)
void UASView::receiveHeartbeat(UASInterface* uas)
{
Q_UNUSED(uas);
QString colorstyle;
heartbeatColor = QColor(20, 200, 20);
colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}",
heartbeatColor.red(), heartbeatColor.green(), heartbeatColor.blue());
m_ui->heartbeatIcon->setStyleSheet(colorstyle);
m_ui->heartbeatIcon->setAutoFillBackground(true);
QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 2px; border: 0px; background-color: %1; }");
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
lastHeartbeat = QGC::groundTimeUsecs();
//m_ui->heartbeatIcon->setAutoFillBackground(true);
}
/**
......@@ -391,6 +398,16 @@ void UASView::updateLoad(UASInterface* uas, double load)
}
}
void UASView::contextMenuEvent (QContextMenuEvent* event)
{
if (QGC::groundTimeUsecs() - lastHeartbeat > 1500000)
{
QMenu menu(this);
menu.addAction(removeAction);
menu.exec(event->globalPos());
}
}
void UASView::refresh()
{
//setUpdatesEnabled(false);
......@@ -494,15 +511,44 @@ void UASView::refresh()
}
generalUpdateCount++;
QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 2px; border: 0px; background-color: %1; }");
if (QGC::groundTimeUsecs() - lastHeartbeat > 1500000)
{
// CRITICAL CONDITION, NO HEARTBEAT
if (iconIsRed)
{
QColor warnColor(Qt::red);
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: %1; }").arg(warnColor.name());
m_ui->uasViewFrame->setStyleSheet(style);
}
else
{
QColor warnColor(Qt::black);
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: %1; }").arg(warnColor.name());
m_ui->uasViewFrame->setStyleSheet(style);
}
iconIsRed = !iconIsRed;
}
else
{
// Break alert once everything is back to normal
if (!iconIsRed)
{
setBackgroundColor();
iconIsRed = true;
}
// Fade heartbeat icon
// Make color darker
heartbeatColor = heartbeatColor.darker(150);
QString colorstyle;
colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 8px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}",
heartbeatColor.red(), heartbeatColor.green(), heartbeatColor.blue());
m_ui->heartbeatIcon->setStyleSheet(colorstyle);
m_ui->heartbeatIcon->setAutoFillBackground(true);
//m_ui->heartbeatIcon->setAutoFillBackground(true);
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
}
//setUpdatesEnabled(true);
//setUpdatesEnabled(false);
......
......@@ -82,6 +82,8 @@ protected:
QTimer* refreshTimer;
QColor heartbeatColor;
quint64 startTime;
quint64 lastHeartbeat;
bool iconIsRed;
int timeRemaining;
float chargeLevel;
UASInterface* uas;
......@@ -100,6 +102,7 @@ protected:
float alt;
float groundDistance;
bool localFrame;
QAction* removeAction;
static const int updateInterval = 300;
......@@ -112,6 +115,7 @@ protected:
void showEvent(QShowEvent* event);
/** @brief Stop widget updating */
void hideEvent(QHideEvent* event);
void contextMenuEvent(QContextMenuEvent* event);
private:
Ui::UASView *m_ui;
......
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