Commit ac110b79 authored by Michael Carpenter's avatar Michael Carpenter

Merge remote-tracking branch 'soren/master'

parents 4f4d88ba c6a96bf7
maah
QGroundControl Open Source Micro Air Vehicle Ground Control Station
Project:
......
From where is the 3D mouse used?
Comm folder:
============
LinkInterface is a QThread. Appears to describe an interface on the host system (TCP port, serial port, ....).
Does it suppport multiple connections?
SerialLinkInterface: Extension of above
SerialLink: Implementation
XBeeLinkInterface: Extension of LinkInterface (but without other serial stuff than baudrate, is the rest assumed?)
XBeeLink: Implementation (with address resetting probably it's Series 1)
UDPLink: UDP implementation. Port is defaulted.
MAVLinkSimulationLink: Simulation/dummy implementation of LinkInterface. Does some file IO.
MAVLinkSimulationUAV: Simulation/dummy basic (remote) UAV state (minus mission state) for MAVLinkSimulationLink.
MAVLinkSimulationWaypointPlanner: imulation/dummy basic (remote) UAV mission state for MAVLinkSimulationLink.
ProtocolInterface describes a protocol. Major method:
virtual void receiveBytes(LinkInterface *link, QByteArray b) = 0;
MavlinkProtocol: MAVLink implementation of ProtocolInterface
Parameter: Identity of a parameter (the value types are not handled here. Oddly there is no type metainfo either)
ParameterList: Is pretty much what the name impiles.
QGCParamID: Wrapper if parameter text IDs, conversion to byte* and back
QGCHilLink: Link to a HIL external system
QCGFlightGearLink, QGCJSBSimLink, QGCXPlaneLink : Implementations of QGCHilLink
QGCMAVLink: Nothing more than in include to raw mavlink.h
input folder:
=============
Some exotic input devices
uas folder:
===========
UAS.h: Local UAV model. Claims to support some sort of RPC. Uses some properties with notifications. Assumes MAVLink.
Some methods:
int getUASID() const; // the systemId
QList<LinkInterface*>* getLinks(); // it knows its links
virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
Some fields:
bool positionLock; ///< Status if position information is available or not
double localX; // (what is this?)
double localY;
double localZ;
double latitude; ///< Global latitude as estimated by position estimator
double longitude; ///< Global longitude as estimated by position estimator
double altitude; ///< Global altitude as estimated by position estimator
double satelliteCount; ///< Number of satellites visible to raw GPS
bool globalEstimatorActive; ///< Global position estimator present, do not fall back to GPS raw for position
double latitude_gps; ///< Global latitude as estimated by raw GPS
double longitude_gps; ///< Global longitude as estimated by raw GPS
double altitude_gps; ///< Global altitude as estimated by raw GPS
and lots ans lots more...
*MAV.h: Implementations of UAS
QGCUASParamManager.h: A mixture of a widget and a parameter up/download state machine. Has a reference to its associated UAV.
UASWaypointManager: API to waypoint / mission control. Not a widget. Has a reference to its associated UAV.
UASManager.h: Singleton interface to all UASs on all interfaces. Maintains a single selected/active UAS.
Ideas to do
TCPLink
XBee Series2 implementation
Less stress on uplink
Get rid of hardcoded SystemId of 255
Quick View should print all altitudes (GPS, mix, ground and/or home), letting user see errors.
Console debugging is hopefully removed?
Major
1) Absolute altitude should absolutely work. Also in face of bad GPS init.
How does the mission planning part work with that, how is alt. stored in waypoints?
When is home altitude stored in the UAV?
2) Some people have worse datalinks than average - eg. slow or noisy telemetry. GPRS data also easily gets
flooded. All data rates should be configurable and uplinks eased off a little.
3) Some streams should be sent always even if not in use. For example using RC override and then stopping
using it: If the UAV does not received the final RC override message with zero values for all channels,
it will not get out of RC override. A solution is to make the message non final, repeating it every
now and then.
Minor
1) I would like to see initial dummy values for eg. battery voltage go away and be replaced by "unknown".
Dummy values confuse, you won't know if your sensors and link are working or not.
2) Suggestion if the DO_JUMP behavior of APM today (where DO_JUMP requires a waypoint command after it):
Modify APM code so DO_JUMP is regarded a navigation command. Make non navigation commands appear in
planning as sub commands of navigation commands (indent them). Easier to understand.
3) Old style audio with signals/bells/beeps / Morse may be prefered by some. Maybe add slots'n'signals for
all audio and different implementation types (speech, beep, ...). Or a generic operator messaging thing.
......@@ -386,7 +386,8 @@ HEADERS += src/MG.h \
src/ui/uas/UASActionsWidget.h \
src/ui/designer/QGCRadioChannelDisplay.h \
src/ui/QGCTabbedInfoView.h \
src/ui/UASRawStatusView.h
src/ui/UASRawStatusView.h \
src/ui/PrimaryFlightDisplay.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
......@@ -560,7 +561,8 @@ SOURCES += src/main.cc \
src/ui/uas/UASActionsWidget.cpp \
src/ui/designer/QGCRadioChannelDisplay.cpp \
src/ui/QGCTabbedInfoView.cpp \
src/ui/UASRawStatusView.cpp
src/ui/UASRawStatusView.cpp \
src/ui/PrimaryFlightDisplay.cpp
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......@@ -693,3 +695,7 @@ win32-msvc2008|win32-msvc2010|win32-msvc2012 {
}
unix:!macx:!symbian: LIBS += -losg
OTHER_FILES += \
dongfang_notes.txt \
src/ui/dongfang-scrapyard.txt
This diff is collapsed.
This diff is collapsed.
......@@ -51,6 +51,42 @@ This file is part of the QGROUNDCONTROL project
#endif
#endif
enum BatteryType
{
NICD = 0,
NIMH = 1,
LIION = 2,
LIPOLY = 3,
LIFE = 4,
AGZN = 5
}; ///< The type of battery used
/*
enum SpeedMeasurementSource
{
PRIMARY_SPEED = 0, // ArduPlane: Measured airspeed or estimated airspeed. ArduCopter: Ground (XY) speed.
GROUNDSPEED_BY_UAV = 1, // Ground speed as reported by UAS
GROUNDSPEED_BY_GPS = 2, // Ground speed as calculated from received GPS velocity data
LOCAL_SPEED = 3
}; ///< For velocity data, the data source
enum AltitudeMeasurementSource
{
PRIMARY_ALTITUDE = 0, // ArduPlane: air and ground speed mix. This is the altitude used for navigastion.
BAROMETRIC_ALTITUDE = 1, // Altitude is pressure altitude. Ardupilot reports no altitude purely by barometer,
// however when ALT_MIX==1, mix-altitude is purely barometric.
GPS_ALTITUDE = 2 // GPS ASL altitude
}; ///< For altitude data, the data source
// TODO!!! The different frames are probably represented elsewhere. There should really only
// be one set of frames. We also need to keep track of the home alt. somehow.
enum AltitudeMeasurementFrame
{
ABSOLUTE = 0, // Altitude is pressure altitude
ABOVE_HOME_POSITION = 1
}; ///< For altitude data, a reference frame
*/
/**
* @brief Interface for all robots.
*
......@@ -470,14 +506,14 @@ signals:
* @param percent remaining capacity in percent
* @param seconds estimated remaining flight time in seconds
*/
void batteryChanged(UASInterface* uas, double voltage, double percent, int seconds);
void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
void statusChanged(UASInterface* uas, QString status);
void actuatorChanged(UASInterface*, int actId, double value);
void thrustChanged(UASInterface*, double thrust);
void heartbeat(UASInterface* uas);
void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
void attitudeChanged(UASInterface*, int component, double roll, double pitch, double yaw, quint64 usec);
void attitudeSpeedChanged(int uas, double rollspeed, double pitchspeed, double yawspeed, quint64 usec);
void attitudeRotationRatesChanged(int uas, double rollrate, double pitchrate, double yawrate, quint64 usec);
void attitudeThrustSetPointChanged(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
/** @brief The MAV set a new setpoint in the local (not body) NED X, Y, Z frame */
void positionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec);
......@@ -486,10 +522,21 @@ signals:
void localPositionChanged(UASInterface*, double x, double y, double z, quint64 usec);
void localPositionChanged(UASInterface*, int component, double x, double y, double z, quint64 usec);
void globalPositionChanged(UASInterface*, double lat, double lon, double alt, quint64 usec);
void altitudeChanged(int uasid, double altitude);
void primaryAltitudeChanged(UASInterface*, double altitude, quint64 usec);
void gpsAltitudeChanged(UASInterface*, double altitude, quint64 usec);
/** @brief Update the status of one satellite used for localization */
void gpsSatelliteStatusChanged(int uasid, int satid, float azimuth, float direction, float snr, bool used);
void speedChanged(UASInterface*, double x, double y, double z, quint64 usec);
// The horizontal speed (a scalar)
void primarySpeedChanged(UASInterface*, double speed, quint64 usec);
void gpsSpeedChanged(UASInterface*, double speed, quint64 usec);
// The vertical speed (a scalar)
void climbRateChanged(UASInterface*, double climb, quint64 usec);
// Consider adding a MAV_FRAME parameter to this; could help specifying what the 3 scalars are.
void velocityChanged_NED(UASInterface*, double vx, double vy, double vz, quint64 usec);
void navigationControllerErrorsChanged(UASInterface*, double altitudeError, double speedError, double xtrackError);
void imageStarted(int imgid, int width, int height, int depth, int channels);
void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex);
/** @brief Emit the new system type */
......
......@@ -41,7 +41,7 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message
emit valueChanged(uasId, "rollspeed", "rad/s", this->m_rotVel[0], time);
emit valueChanged(uasId, "pitchspeed", "rad/s", this->m_rotVel[1], time);
emit valueChanged(uasId, "yawspeed", "rad/s", this->m_rotVel[2], time);
emit attitudeSpeedChanged(uasId, this->m_rotVel[0], this->m_rotVel[1], this->m_rotVel[2], time);
emit attitudeRotationRatesChanged(uasId, this->m_rotVel[0], this->m_rotVel[1], this->m_rotVel[2], time);
break;
}
case MAVLINK_MSG_ID_LLC_OUT: // low level controller output
......@@ -62,7 +62,7 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message
mavlink_obs_air_temp_t airTMsg;
mavlink_msg_obs_air_temp_decode(&message,&airTMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Air Temp", "", airTMsg.airT, time);
emit valueChanged(uasId, "Air Temp", "°", airTMsg.airT, time);
break;
}
case MAVLINK_MSG_ID_OBS_AIR_VELOCITY:
......@@ -211,4 +211,4 @@ void senseSoarMAV::quat2euler(const double *quat, double &roll, double &pitch, d
pitch = std::asin(qMax(-1.0,qMin(1.0,2*(quat[0]*quat[2] - quat[1]*quat[3]))));
yaw = std::atan2(2*(quat[1]*quat[2] + quat[0]*quat[3]),quat[0]*quat[0] + quat[1]*quat[1] - quat[2]*quat[2] - quat[3]*quat[3]);
return;
}
\ No newline at end of file
}
......@@ -178,7 +178,10 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage()));
statusClearTimer.start(3000);
setActiveUAS(UASManager::instance()->getActiveUAS());
if (UASManager::instance()->getActiveUAS())
{
setActiveUAS(UASManager::instance()->getActiveUAS());
}
setFocusPolicy(Qt::StrongFocus);
}
......@@ -864,7 +867,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
disconnect(this->uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
disconnect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
......@@ -895,7 +898,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
......
......@@ -119,7 +119,7 @@ HUD::HUD(int width, int height, QWidget* parent)
load(0.0f),
offlineDirectory(""),
nextOfflineImage(""),
hudInstrumentsEnabled(true),
HUDInstrumentsEnabled(true),
videoEnabled(false),
xImageFactor(1.0),
yImageFactor(1.0),
......@@ -218,7 +218,7 @@ void HUD::contextMenuEvent (QContextMenuEvent* event)
{
QMenu menu(this);
// Update actions
enableHUDAction->setChecked(hudInstrumentsEnabled);
enableHUDAction->setChecked(HUDInstrumentsEnabled);
enableVideoAction->setChecked(videoEnabled);
menu.addAction(enableHUDAction);
......@@ -234,7 +234,7 @@ void HUD::createActions()
enableHUDAction = new QAction(tr("Enable HUD"), this);
enableHUDAction->setStatusTip(tr("Show the HUD instruments in this window"));
enableHUDAction->setCheckable(true);
enableHUDAction->setChecked(hudInstrumentsEnabled);
enableHUDAction->setChecked(HUDInstrumentsEnabled);
connect(enableHUDAction, SIGNAL(triggered(bool)), this, SLOT(enableHUDInstruments(bool)));
enableVideoAction = new QAction(tr("Enable Video Live feed"), this);
......@@ -261,16 +261,16 @@ void HUD::setActiveUAS(UASInterface* uas)
{
if (this->uas != NULL) {
// Disconnect any previously connected active MAV
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64)));
disconnect(this->uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*, double, double, double, quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int, double, double, double, quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64)));
disconnect(this->uas, SIGNAL(batteryChanged(UASInterface*, double, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, double, int)));
disconnect(this->uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString)));
disconnect(this->uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
disconnect(this->uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(velocityChanged_NEDspeedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
// Try to disconnect the image link
......@@ -286,14 +286,14 @@ void HUD::setActiveUAS(UASInterface* uas)
// Setup communication
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64)));
connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, double, int)));
connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString)));
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
connect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
// Try to connect the image link
......@@ -338,10 +338,11 @@ void HUD::updateAttitude(UASInterface* uas, int component, double roll, double p
}
}
void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
void HUD::updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds)
{
Q_UNUSED(uas);
Q_UNUSED(seconds);
Q_UNUSED(current);
fuelStatus = tr("BAT [%1% | %2V]").arg(percent, 2, 'f', 0, QChar('0')).arg(voltage, 4, 'f', 1, QChar('0'));
if (percent < 20.0f) {
fuelColor = warningColor;
......@@ -711,7 +712,7 @@ void HUD::paintHUD()
// END OF OPENGL PAINTING
if (hudInstrumentsEnabled) {
if (HUDInstrumentsEnabled) {
//glEnable(GL_MULTISAMPLE);
......@@ -1459,7 +1460,7 @@ void HUD::selectOfflineDirectory()
void HUD::enableHUDInstruments(bool enabled)
{
hudInstrumentsEnabled = enabled;
HUDInstrumentsEnabled = enabled;
}
void HUD::enableVideo(bool enabled)
......@@ -1509,7 +1510,7 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s
void HUD::copyImage()
{
if (isVisible() && hudInstrumentsEnabled)
if (isVisible() && HUDInstrumentsEnabled)
{
//qDebug() << "HUD::copyImage()";
UAS* u = dynamic_cast<UAS*>(this->uas);
......
......@@ -69,7 +69,7 @@ public slots:
/** @brief Attitude from one specific component / redundant autopilot */
void updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp);
// void updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
void updateBattery(UASInterface*, double, double, int);
void updateBattery(UASInterface*, double, double, double, int);
void receiveHeartbeat(UASInterface*);
void updateThrust(UASInterface*, double);
void updateLocalPosition(UASInterface*,double,double,double,quint64);
......@@ -184,7 +184,7 @@ protected:
int warningBlinkRate; ///< Blink rate of warning messages, will be rounded to the refresh rate
QTimer* refreshTimer; ///< The main timer, controls the update rate
QPainter* hudPainter;
QPainter* HUDPainter;
QFont font; ///< The HUD font, per default the free Bitstream Vera SANS, which is very close to actual HUD fonts
QFontDatabase fontDatabase;///< Font database, only used to load the TrueType font file (the HUD font is directly loaded from file rather than from the system)
bool noCamera; ///< No camera images available, draw the ground/sky box to indicate the horizon
......@@ -218,7 +218,7 @@ protected:
float load;
QString offlineDirectory;
QString nextOfflineImage;
bool hudInstrumentsEnabled;
bool HUDInstrumentsEnabled;
bool videoEnabled;
bool dataStreamEnabled;
bool imageLoggingEnabled;
......
......@@ -62,6 +62,8 @@ This file is part of the QGROUNDCONTROL project
#include "UASActionsWidget.h"
#include "QGCTabbedInfoView.h"
#include "UASRawStatusView.h"
#include "PrimaryFlightDisplay.h"
#ifdef QGC_OSG_ENABLED
#include "Q3DWidgetFactory.h"
#endif
......@@ -357,7 +359,6 @@ QString MainWindow::getWindowStateKey()
return QString::number(currentView)+"_windowstate_" + UASManager::instance()->getActiveUAS()->getAutopilotTypeName();
}
else
return QString::number(currentView)+"_windowstate";
}
......@@ -589,11 +590,11 @@ 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(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,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 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);
......@@ -607,6 +608,14 @@ void MainWindow::buildCommonWidgets()
createDockWidget(pilotView,infoview,tr("Info View"),"UAS_INFO_INFOVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
//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 PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_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);
// createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
// pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North);
// pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]);
//UASRawStatusView *view = new UASRawStatusView();
//view->setDecoder(mavlinkDecoder);
//view->show();
......@@ -764,7 +773,12 @@ void MainWindow::loadDockWidget(QString name)
{
return;
}
if (name == "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET")
if (name.startsWith("HIL_CONFIG"))
{
//It's a HIL widget.
showHILConfigurationWidget(UASManager::instance()->getActiveUAS());
}
else if (name == "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET")
{
createDockWidget(centerStack->currentWidget(),new UASControlWidget(this),tr("Control"),"UNMANNED_SYSTEM_CONTROL_DOCKWIDGET",currentView,Qt::LeftDockWidgetArea);
}
......@@ -823,9 +837,10 @@ void MainWindow::loadDockWidget(QString name)
qDebug() << "Error loading window:" << name << "Unknown window type";
//createDockWidget(centerStack->currentWidget(),hddisplay,tr("Actuator Status"),"HEADS_DOWN_DISPLAY_2_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
}
else if (name == "HEAD_UP_DISPLAY_DOCKWIDGET")
else if (name == "PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET")
{
createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
// createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
createDockWidget(centerStack->currentWidget(),new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
}
else if (name == "UAS_INFO_QUICKVIEW_DOCKWIDGET")
{
......@@ -921,8 +936,11 @@ void MainWindow::showHILConfigurationWidget(UASInterface* uas)
if (mav && !hilDocks.contains(mav->getUASID()))
{
//QGCToolWidget* tool = new QGCToolWidget("Unnamed Tool " + QString::number(ui.menuTools->actions().size()));
//createDockWidget(centerStack->currentWidget(),tool,"Unnamed Tool " + QString::number(ui.menuTools->actions().size()),"UNNAMED_TOOL_" + QString::number(ui.menuTools->actions().size())+"DOCK",currentView,Qt::BottomDockWidgetArea);
QGCHilConfiguration* hconf = new QGCHilConfiguration(mav, this);
QString hilDockName = tr("HIL Config %1").arg(uas->getUASName());
QString hilDockName = tr("HIL Config %1").arg(uas->getUASName());
QDockWidget* hilDock = createDockWidget(simView, hconf,hilDockName, hilDockName.toUpper().replace(" ", "_"),VIEW_SIMULATION,Qt::LeftDockWidgetArea);
hilDocks.insert(mav->getUASID(), hilDock);
......@@ -936,8 +954,8 @@ void MainWindow::showHILConfigurationWidget(UASInterface* uas)
void MainWindow::closeEvent(QCloseEvent *event)
{
if (isVisible()) storeViewState();
storeSettings();
aboutToCloseFlag = true;
storeSettings();
mavlink->storeSettings();
UASManager::instance()->storeSettings();
QMainWindow::closeEvent(event);
......
This diff is collapsed.
#ifndef PRIMARYFLIGHTDISPLAY_H
#define PRIMARYFLIGHTDISPLAY_H
#include <QWidget>
#include <QPen>
#include "UASInterface.h"
#define SEPARATE_COMPASS_ASPECTRATIO (3.0f/4.0f)
#define LINEWIDTH 0.0036f
//#define TAPES_TEXT_SIZE 0.028
//#define AI_TEXT_SIZE 0.040
//#define AI_TEXT_MIN_PIXELS 12
//#define AI_TEXT_MAX_PIXELS 36
//#define PANELS_TEXT_SIZE 0.030
//#define COMPASS_SCALE_TEXT_SIZE 0.16
#define SMALL_TEXT_SIZE 0.03f
#define MEDIUM_TEXT_SIZE (SMALL_TEXT_SIZE*1.2f)
#define LARGE_TEXT_SIZE (MEDIUM_TEXT_SIZE*1.2f)
#define SHOW_ZERO_ON_SCALES true
// all in units of display height
#define ROLL_SCALE_RADIUS 0.42f
#define ROLL_SCALE_TICKMARKLENGTH 0.04f
#define ROLL_SCALE_MARKERWIDTH 0.06f
#define ROLL_SCALE_MARKERHEIGHT 0.04f
// scale max. degrees
#define ROLL_SCALE_RANGE 60
// fraction of height to translate for each degree of pitch.
#define PITCHTRANSLATION 65.0
// 10 degrees for each line
#define PITCH_SCALE_RESOLUTION 5
#define PITCH_SCALE_MAJORWIDTH 0.1
#define PITCH_SCALE_MINORWIDTH 0.066
// Beginning from PITCH_SCALE_WIDTHREDUCTION_FROM degrees of +/- pitch, the
// width of the lines is reduced, down to PITCH_SCALE_WIDTHREDUCTION times
// the normal width. This helps keep orientation in extreme attitudes.
#define PITCH_SCALE_WIDTHREDUCTION_FROM 30
#define PITCH_SCALE_WIDTHREDUCTION 0.3
#define PITCH_SCALE_HALFRANGE 15
// The number of degrees to either side of the heading to draw the compass disk.
// 180 is valid, this will draw a complete disk. If the disk is partly clipped
// away, less will do.
#define COMPASS_DISK_MAJORTICK 10
#define COMPASS_DISK_ARROWTICK 45
#define COMPASS_DISK_MAJORLINEWIDTH 0.006
#define COMPASS_DISK_MINORLINEWIDTH 0.004
#define COMPASS_DISK_RESOLUTION 10
#define COMPASS_SEPARATE_DISK_RESOLUTION 5
#define COMPASS_DISK_MARKERWIDTH 0.2
#define COMPASS_DISK_MARKERHEIGHT 0.133
#define CROSSTRACK_MAX 1000
#define CROSSTRACK_RADIUS 0.6
#define TAPE_GAUGES_TICKWIDTH_MAJOR 0.25
#define TAPE_GAUGES_TICKWIDTH_MINOR 0.15
// The altitude difference between top and bottom of scale
#define ALTIMETER_LINEAR_SPAN 50
// every 5 meters there is a tick mark
#define ALTIMETER_LINEAR_RESOLUTION 5
// every 10 meters there is a number
#define ALTIMETER_LINEAR_MAJOR_RESOLUTION 10
// Projected: An experiment. Make tape appear projected from a cylinder, like a French "drum" style gauge.
// The altitude difference between top and bottom of scale
#define ALTIMETER_PROJECTED_SPAN 50
// every 5 meters there is a tick mark
#define ALTIMETER_PROJECTED_RESOLUTION 5
// every 10 meters there is a number
#define ALTIMETER_PROJECTED_MAJOR_RESOLUTION 10
// min. and max. vertical velocity
//#define ALTIMETER_PROJECTED
// min. and max. vertical velocity
#define ALTIMETER_VVI_SPAN 5
#define ALTIMETER_VVI_WIDTH 0.2
// Now the same thing for airspeed!
#define AIRSPEED_LINEAR_SPAN 15
#define AIRSPEED_LINEAR_RESOLUTION 1
#define AIRSPEED_LINEAR_MAJOR_RESOLUTION 5
#define UNKNOWN_BATTERY -1
#define UNKNOWN_ATTITUDE 0
#define UNKNOWN_ALTITUDE -1000
#define UNKNOWN_SPEED -1
#define UNKNOWN_COUNT -1
#define UNKNOWN_GPSFIXTYPE -1
class PrimaryFlightDisplay : public QWidget
{
Q_OBJECT
public:
PrimaryFlightDisplay(int width = 640, int height = 480, QWidget* parent = NULL);
~PrimaryFlightDisplay();
public slots:
/** @brief Attitude from main autopilot / system state */
void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp);
/** @brief Attitude from one specific component / redundant autopilot */
void updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp);
void updatePrimarySpeed(UASInterface* uas, double speed, quint64 timstamp);
void updateGPSSpeed(UASInterface* uas, double speed, quint64 timstamp);
void updateClimbRate(UASInterface* uas, double altitude, quint64 timestamp);
void updatePrimaryAltitude(UASInterface* uas, double altitude, quint64 timestamp);
void updateGPSAltitude(UASInterface* uas, double altitude, quint64 timestamp);
void updateNavigationControllerErrors(UASInterface* uas, double altitudeError, double speedError, double xtrackError);
/** @brief Set the currently monitored UAS */
virtual void setActiveUAS(UASInterface* uas);
protected:
enum Layout {
COMPASS_INTEGRATED,
COMPASS_SEPARATED // For a very high container. Feature panels are at bottom.
};
enum Style {
NO_OVERLAYS, // Hzon not visible through tapes nor through feature panels. Frames with margins between.
OVERLAY_HORIZONTAL, // Hzon visible through tapes and (frameless) feature panels.
OVERLAY_HSI // Hzon visible through everything except bottom feature panels.
};
void paintEvent(QPaintEvent *event);
void resizeEvent(QResizeEvent *e);
// from HUD.h:
/** @brief Preferred Size */
QSize sizeHint() const;
/** @brief Start updating widget */
void showEvent(QShowEvent* event);
/** @brief Stop updating widget */
void hideEvent(QHideEvent* event);
// dongfang: We have no context menu. Viewonly.
// void contextMenuEvent (QContextMenuEvent* event);
// dongfang: What is that?
// dongfang: OK it's for UI interaction. Presently, there is none.
void createActions();
signals:
void visibilityChanged(bool visible);
private:
enum AltimeterMode {
PRIMARY_MAIN_GPS_SUB, // Show the primary alt. on tape and GPS as extra info
GPS_MAIN // Show GPS on tape and no extra info
};
enum AltimeterFrame {
ASL, // Show ASL altitudes (plane pilots' normal preference)
RELATIVE_TO_HOME // Show relative-to-home altitude (copter pilots)
};
enum SpeedMode {
PRIMARY_MAIN_GROUND_SUB,// Show primary speed (often airspeed) on tape and groundspeed as extra
GROUND_MAIN // Show groundspeed on tape and no extra info
};
/*
* There are at least these differences between airplane and copter PDF view:
* - Airplane show absolute altutude in altimeter, copter shows relative to home
*/
bool isAirplane();
bool shouldDisplayNavigationData();
void drawTextCenter(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextLeftCenter(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextRightCenter(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextCenterBottom(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextCenterTop(QPainter& painter, QString text, float fontSize, float x, float y);
void drawAIGlobalFeatures(QPainter& painter, QRectF mainArea, QRectF paintArea);
void drawAIAirframeFixedFeatures(QPainter& painter, QRectF area);
void drawPitchScale(QPainter& painter, QRectF area, float intrusion, bool drawNumbersLeft, bool drawNumbersRight);
void drawRollScale(QPainter& painter, QRectF area, bool drawTicks, bool drawNumbers);
void drawAIAttitudeScales(QPainter& painter