Commit 6f3376a2 authored by Lorenz Meier's avatar Lorenz Meier

Merge

parents 44e5b5d6 eeda94f3
......@@ -27,6 +27,15 @@ This file is part of the QGROUNDCONTROL project
*/
#include "ArduPilotMegaMAV.h"
#ifndef mavlink_mount_configure_t
#include "ardupilotmega/mavlink_msg_mount_configure.h"
#endif
#ifndef mavlink_mount_control_t
#include "ardupilotmega/mavlink_msg_mount_control.h";
#endif
ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)//,
// place other initializers here
......
......@@ -2026,15 +2026,13 @@ QImage UAS::getImage()
// RAW greyscale
if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
{
// TODO FIXME
int imgColors = 255;//imageSize/(imageWidth*imageHeight);
//const int headerSize = 15;
int imgColors = 255;
// Construct PGM header
QString header("P5\n%1 %2\n%3\n");
header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size());
QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size() - 1);
tmpImage.append(imageRecBuffer);
//qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;
......@@ -2047,7 +2045,7 @@ QImage UAS::getImage()
if (!image.loadFromData(tmpImage, "PGM"))
{
qDebug()<< "could not create extracted image";
qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
return QImage();
}
......@@ -2060,7 +2058,7 @@ QImage UAS::getImage()
{
if (!image.loadFromData(imageRecBuffer))
{
qDebug() << "Loading data from image buffer failed!";
qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
}
}
// Restart statemachine
......
......@@ -34,6 +34,7 @@ This file is part of the QGROUNDCONTROL project
#include <QMenu>
#include <QDesktopServices>
#include <QFileDialog>
#include <QPaintEvent>
#include <QDebug>
#include <cmath>
......@@ -43,15 +44,9 @@ This file is part of the QGROUNDCONTROL project
#include "UASManager.h"
#include "UAS.h"
#include "HUD.h"
#include "MG.h"
#include "QGC.h"
#include "MainWindow.h"
// Fix for some platforms, e.g. windows
#ifndef GL_MULTISAMPLE
#define GL_MULTISAMPLE 0x809D
#endif
/**
* @warning The HUD widget will not start painting its content automatically
* to update the view, start the auto-update by calling HUD::start().
......@@ -61,7 +56,7 @@ This file is part of the QGROUNDCONTROL project
* @param parent
*/
HUD::HUD(int width, int height, QWidget* parent)
: QWidget(parent),
: QLabel(parent),
uas(NULL),
yawInt(0.0f),
mode(tr("UNKNOWN MODE")),
......@@ -114,12 +109,13 @@ HUD::HUD(int width, int height, QWidget* parent)
load(0.0f),
offlineDirectory(""),
nextOfflineImage(""),
HUDInstrumentsEnabled(true),
HUDInstrumentsEnabled(false),
videoEnabled(true),
xImageFactor(1.0),
yImageFactor(1.0),
imageLoggingEnabled(false),
imageRequested(false)
image(NULL)
{
// Set auto fill to false
setAutoFillBackground(false);
......@@ -136,18 +132,10 @@ HUD::HUD(int width, int height, QWidget* parent)
// Refresh timer
refreshTimer->setInterval(updateInterval);
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD()));
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(repaint()));
// Resize to correct size and fill with image
QWidget::resize(this->width(), this->height());
//glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits());
// Set size once
//setFixedSize(fill.size());
//setMinimumSize(fill.size());
//setMaximumSize(fill.size());
// Lock down the size
//setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
fontDatabase = QFontDatabase();
const QString fontFileName = ":/general/vera.ttf"; ///< Font file is part of the QRC file and compiled into the app
......@@ -527,10 +515,8 @@ void HUD::paintRollPitchStrips()
void HUD::paintEvent(QPaintEvent *event)
{
// Event is not needed
// the event is ignored as this widget
// is refreshed automatically
Q_UNUSED(event);
paintHUD();
}
void HUD::paintHUD()
......@@ -611,6 +597,13 @@ void HUD::paintHUD()
}
QPainter painter;
painter.begin(this);
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
QPixmap pmap = QPixmap::fromImage(glImage).scaledToWidth(width());
painter.drawPixmap(0, (height() - pmap.height()) / 2, pmap);
// END OF OPENGL PAINTING
if (HUDInstrumentsEnabled)
......@@ -620,10 +613,7 @@ void HUD::paintHUD()
// QT PAINTING
//makeCurrent();
QPainter painter;
painter.begin(this);
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
painter.translate((this->vwidth/2.0+xCenterOffset)*scalingFactor, (this->vheight/2.0+yCenterOffset)*scalingFactor);
// COORDINATE FRAME IS NOW (0,0) at CENTER OF WIDGET
......@@ -784,13 +774,12 @@ void HUD::paintHUD()
painter.rotate(-(att.x()/M_PI)* -180.0f);
}
painter.end();
} else {
QPainter painter;
painter.begin(this);
painter.end();
}
painter.end();
}
}
......@@ -1225,7 +1214,8 @@ void HUD::setImageSize(int width, int height, int depth, int channels)
rawBuffer1 = (unsigned char*)malloc(rawExpectedBytes);
rawBuffer2 = (unsigned char*)malloc(rawExpectedBytes);
rawImage = rawBuffer1;
// TODO check if old image should be deleted
if (image)
delete image;
// Set image format
// 8 BIT GREYSCALE IMAGE
......@@ -1399,9 +1389,6 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s
void HUD::copyImage()
{
if (isVisible() && HUDInstrumentsEnabled)
{
//qDebug() << "HUD::copyImage()";
UAS* u = dynamic_cast<UAS*>(this->uas);
if (u)
{
......@@ -1414,7 +1401,6 @@ void HUD::copyImage()
imageLogCounter++;
}
}
}
}
void HUD::saveImages(bool save)
......
......@@ -34,6 +34,7 @@ This file is part of the QGROUNDCONTROL project
#include <QImage>
#include <QWidget>
#include <QLabel>
#include <QPainter>
#include <QFontDatabase>
#include <QTimer>
......@@ -48,7 +49,7 @@ This file is part of the QGROUNDCONTROL project
* It can superimpose the HUD over the current live image stream (any arriving image stream will be auto-
* matically used as background), or it draws the classic blue-brown background known from instruments.
*/
class HUD : public QWidget
class HUD : public QLabel
{
Q_OBJECT
public:
......@@ -139,7 +140,7 @@ protected:
void contextMenuEvent (QContextMenuEvent* event);
void createActions();
static const int updateInterval = 40;
static const int updateInterval = 100;
QImage* image; ///< Double buffer image
QImage glImage; ///< The background / camera image
......
......@@ -17,8 +17,9 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
}
// Fill filter
messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false);
messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false);
// Allow system status
// messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false);
// messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false);
messageFilter.insert(MAVLINK_MSG_ID_STATUSTEXT, false);
messageFilter.insert(MAVLINK_MSG_ID_COMMAND_LONG, false);
messageFilter.insert(MAVLINK_MSG_ID_COMMAND_ACK, false);
......@@ -200,7 +201,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// Add field tree widget item
uint8_t msgid = msg->msgid;
//if (messageFilter.contains(msgid)) return;
if (messageFilter.contains(msgid)) return;
QString fieldName(messageInfo[msgid].fields[fieldid].name);
QString fieldType;
uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
......
......@@ -482,11 +482,7 @@ void MainWindow::buildCommonWidgets()
{
pilotView = new SubMainWindow(this);
pilotView->setObjectName("VIEW_FLIGHT");
//pilotView->setCentralWidget(new HUD(320,240,this));
pilotView->setCentralWidget(new QGCMapTool(this));
//hudWidget = new HUD(320, 240, this);
//addCentralWidget(hudWidget, tr("Head Up Display"));
//mapWidget = new QGCMapTool(this);
addCentralWidget(pilotView, "Pilot");
}
if (!configView)
......@@ -586,18 +582,9 @@ void MainWindow::buildCommonWidgets()
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
}
// createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5);
createDockWidget(engineeringView,new HUD(320,240,this),tr("Video Downlink"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea,this->width()/1.5);
createDockWidget(simView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5);
//createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea);
// createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
//createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
//UASQuickView *quickview = new UASQuickView(this);
//quickview->addSource(mavlinkDecoder);
//createDockWidget(pilotView,quickview,tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
createDockWidget(pilotView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
QGCTabbedInfoView *infoview = new QGCTabbedInfoView(this);
......
......@@ -60,16 +60,11 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
connect(ui->generalMenuButton,SIGNAL(clicked()),this,SLOT(generalMenuButtonClicked()));
connect(ui->advancedMenuButton,SIGNAL(clicked()),this,SLOT(advancedMenuButtonClicked()));
requestCalibrationRC();
if (mav) mav->requestParameter(0, "RC_TYPE");
ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);
ui->rcCalibrationButton->setCheckable(true);
connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
connect(ui->setButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
connect(ui->refreshButton,SIGNAL(clicked()),mav,SLOT(requestParameters()));
connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
//connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));
......@@ -798,6 +793,21 @@ void QGCVehicleConfig::loadConfig()
void QGCVehicleConfig::setActiveUAS(UASInterface* active)
{
// Hide items if NULL and abort
if (!active) {
ui->setButton->setEnabled(false);
ui->refreshButton->setEnabled(false);
ui->readButton->show();
ui->readButton->setEnabled(false);
ui->writeButton->show();
ui->writeButton->setEnabled(false);
ui->loadFileButton->setEnabled(false);
ui->saveFileButton->setEnabled(false);
return;
}
// Do nothing if system is the same
if (mav == active) return;
......@@ -808,6 +818,7 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
SLOT(remoteControlChannelRawChanged(int,float)));
disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
SLOT(parameterChanged(int,int,QString,QVariant)));
disconnect(ui->refreshButton,SIGNAL(clicked()),mav,SLOT(requestParameters()));
// Delete all children from all fixed tabs.
foreach(QWidget* child, ui->generalLeftContents->findChildren<QWidget*>())
......@@ -846,19 +857,23 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
paramTooltips.clear();
}
// Connect new system
mav = active;
// Reset current state
resetCalibrationRC();
requestCalibrationRC();
mav->requestParameter(0, "RC_TYPE");
chanCount = 0;
// Connect new system
mav = active;
if (mav)
{
connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
SLOT(remoteControlChannelRawChanged(int,float)));
connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
SLOT(parameterChanged(int,int,QString,QVariant)));
connect(ui->refreshButton, SIGNAL(clicked()), active, SLOT(requestParameters()));
if (systemTypeToParamMap.contains(mav->getSystemTypeName()))
{
......@@ -896,18 +911,6 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
ui->readButton->hide();
ui->writeButton->hide();
}
}
else
{
ui->setButton->setEnabled(false);
ui->refreshButton->setEnabled(false);
ui->readButton->show();
ui->readButton->setEnabled(false);
ui->writeButton->show();
ui->writeButton->setEnabled(false);
ui->loadFileButton->setEnabled(false);
ui->saveFileButton->setEnabled(false);
}
}
void QGCVehicleConfig::resetCalibrationRC()
......
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