Commit aba48800 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #4570 from dogmaphobic/toolBar

Removing toolbar controller
parents 7e41ed7b e3233321
......@@ -487,7 +487,6 @@ HEADERS += \
src/uas/UAS.h \
src/uas/UASInterface.h \
src/uas/UASMessageHandler.h \
src/ui/toolbar/MainToolBarController.h \
DebugBuild {
HEADERS += \
......@@ -647,7 +646,6 @@ SOURCES += \
src/main.cc \
src/uas/UAS.cc \
src/uas/UASMessageHandler.cc \
src/ui/toolbar/MainToolBarController.cc \
DebugBuild {
SOURCES += \
......
......@@ -64,7 +64,6 @@
#include "QGroundControlQmlGlobal.h"
#include "FlightMapSettings.h"
#include "CoordinateVector.h"
#include "MainToolBarController.h"
#include "MissionController.h"
#include "GeoFenceController.h"
#include "RallyPointController.h"
......@@ -378,7 +377,6 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<ParameterEditorController> ("QGroundControl.Controllers", 1, 0, "ParameterEditorController");
qmlRegisterType<ESP8266ComponentController> ("QGroundControl.Controllers", 1, 0, "ESP8266ComponentController");
qmlRegisterType<ScreenToolsController> ("QGroundControl.Controllers", 1, 0, "ScreenToolsController");
qmlRegisterType<MainToolBarController> ("QGroundControl.Controllers", 1, 0, "MainToolBarController");
qmlRegisterType<MissionController> ("QGroundControl.Controllers", 1, 0, "MissionController");
qmlRegisterType<GeoFenceController> ("QGroundControl.Controllers", 1, 0, "GeoFenceController");
qmlRegisterType<RallyPointController> ("QGroundControl.Controllers", 1, 0, "RallyPointController");
......
......@@ -101,6 +101,13 @@ Vehicle::Vehicle(LinkInterface* link,
, _globalPositionIntMessageAvailable(false)
, _cruiseSpeed(QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->rawValue().toDouble())
, _hoverSpeed(QGroundControlQmlGlobal::offlineEditingHoverSpeed()->rawValue().toDouble())
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
, _telemetryRXErrors(0)
, _telemetryFixed(0)
, _telemetryTXBuffer(0)
, _telemetryLNoise(0)
, _telemetryRNoise(0)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(NULL)
......@@ -148,6 +155,7 @@ Vehicle::Vehicle(LinkInterface* link,
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(_mavlink, &MAVLinkProtocol::radioStatusChanged, this, &Vehicle::_telemetryChanged);
connect(this, &Vehicle::_sendMessageOnLinkOnThread, this, &Vehicle::_sendMessageOnLink, Qt::QueuedConnection);
connect(this, &Vehicle::flightModeChanged, this, &Vehicle::_handleFlightModeChanged);
......@@ -408,6 +416,37 @@ void Vehicle::resetCounters()
_heardFrom = false;
}
void Vehicle::_telemetryChanged(LinkInterface*, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise)
{
if(_telemetryLRSSI != rssi) {
_telemetryLRSSI = rssi;
emit telemetryLRSSIChanged(_telemetryLRSSI);
}
if(_telemetryRRSSI != remrssi) {
_telemetryRRSSI = remrssi;
emit telemetryRRSSIChanged(_telemetryRRSSI);
}
if(_telemetryRXErrors != rxerrors) {
_telemetryRXErrors = rxerrors;
emit telemetryRXErrorsChanged(_telemetryRXErrors);
}
if(_telemetryFixed != fixed) {
_telemetryFixed = fixed;
emit telemetryFixedChanged(_telemetryFixed);
}
if(_telemetryTXBuffer != txbuf) {
_telemetryTXBuffer = txbuf;
emit telemetryTXBufferChanged(_telemetryTXBuffer);
}
if(_telemetryLNoise != noise) {
_telemetryLNoise = noise;
emit telemetryLNoiseChanged(_telemetryLNoise);
}
if(_telemetryRNoise != remnoise) {
_telemetryRNoise = remnoise;
emit telemetryRNoiseChanged(_telemetryRNoise);
}
}
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{
......@@ -1306,8 +1345,8 @@ QStringList Vehicle::joystickModes(void)
void Vehicle::_activeJoystickChanged(void)
{
_loadSettings();
_startJoystick(true);
_loadSettings();
_startJoystick(true);
}
bool Vehicle::joystickEnabled(void)
......
......@@ -268,6 +268,13 @@ public:
Q_PROPERTY(QString vehicleImageOpaque READ vehicleImageOpaque CONSTANT)
Q_PROPERTY(QString vehicleImageOutline READ vehicleImageOutline CONSTANT)
Q_PROPERTY(QString vehicleImageCompass READ vehicleImageCompass CONSTANT)
Q_PROPERTY(int telemetryRRSSI READ telemetryRRSSI NOTIFY telemetryRRSSIChanged)
Q_PROPERTY(int telemetryLRSSI READ telemetryLRSSI NOTIFY telemetryLRSSIChanged)
Q_PROPERTY(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged)
Q_PROPERTY(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged)
Q_PROPERTY(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged)
Q_PROPERTY(unsigned int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged)
Q_PROPERTY(unsigned int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY(bool flying READ flying WRITE setFlying NOTIFY flyingChanged)
......@@ -525,7 +532,14 @@ public:
double cruiseSpeed () const { return _cruiseSpeed; }
double hoverSpeed () const { return _hoverSpeed; }
QString firmwareTypeString () const;
QString vehicleTypeString () const;
QString vehicleTypeString () const;
int telemetryRRSSI () { return _telemetryRRSSI; }
int telemetryLRSSI () { return _telemetryLRSSI; }
unsigned int telemetryRXErrors () { return _telemetryRXErrors; }
unsigned int telemetryFixed () { return _telemetryFixed; }
unsigned int telemetryTXBuffer () { return _telemetryTXBuffer; }
unsigned int telemetryLNoise () { return _telemetryLNoise; }
unsigned int telemetryRNoise () { return _telemetryRNoise; }
Fact* roll (void) { return &_rollFact; }
Fact* heading (void) { return &_headingFact; }
......@@ -632,16 +646,23 @@ signals:
/// Used internally to move sendMessage call to main thread
void _sendMessageOnLinkOnThread(LinkInterface* link, mavlink_message_t message);
void messageTypeChanged ();
void newMessageCountChanged ();
void messageCountChanged ();
void formatedMessagesChanged();
void formatedMessageChanged ();
void latestErrorChanged ();
void longitudeChanged ();
void currentConfigChanged ();
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
void messageTypeChanged ();
void newMessageCountChanged ();
void messageCountChanged ();
void formatedMessagesChanged ();
void formatedMessageChanged ();
void latestErrorChanged ();
void longitudeChanged ();
void currentConfigChanged ();
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
void telemetryRRSSIChanged (int value);
void telemetryLRSSIChanged (int value);
void telemetryRXErrorsChanged (unsigned int value);
void telemetryFixedChanged (unsigned int value);
void telemetryTXBufferChanged (unsigned int value);
void telemetryLNoiseChanged (unsigned int value);
void telemetryRNoiseChanged (unsigned int value);
void firmwareMajorVersionChanged(int major);
void firmwareMinorVersionChanged(int minor);
......@@ -674,6 +695,7 @@ signals:
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
void _telemetryChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
void _linkInactiveOrDeleted(LinkInterface* link);
void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
void _sendMessageMultipleNext(void);
......@@ -789,6 +811,13 @@ private:
bool _globalPositionIntMessageAvailable;
double _cruiseSpeed;
double _hoverSpeed;
int _telemetryRRSSI;
int _telemetryLRSSI;
uint32_t _telemetryRXErrors;
uint32_t _telemetryFixed;
uint32_t _telemetryTXBuffer;
uint32_t _telemetryLNoise;
uint32_t _telemetryRNoise;
typedef struct {
int component;
......
......@@ -42,8 +42,6 @@ Rectangle {
signal showFlyView
signal showAnalyzeView
MainToolBarController { id: _controller }
function checkSettingsButton() {
settingsButton.checked = true
}
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
/**
* @file
* @brief QGC Main Tool Bar
* @author Gus Grubba <mavlink@grubba.com>
*/
#include <QQmlContext>
#include <QQmlEngine>
#include "MainToolBarController.h"
#include "ScreenToolsController.h"
#include "UASMessageView.h"
#include "UASMessageHandler.h"
#include "QGCApplication.h"
#include "MultiVehicleManager.h"
#include "UAS.h"
#include "ParameterManager.h"
MainToolBarController::MainToolBarController(QObject* parent)
: QObject(parent)
, _vehicle(NULL)
, _mav(NULL)
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
{
_activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle());
connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::radioStatusChanged, this, &MainToolBarController::_telemetryChanged);
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged);
}
MainToolBarController::~MainToolBarController()
{
}
void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
{
// Disconnect the previous one (if any)
if (_vehicle) {
_mav = NULL;
_vehicle = NULL;
}
// Connect new system
if (vehicle)
{
_vehicle = vehicle;
_mav = vehicle->uas();
}
}
void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise)
{
if(_telemetryLRSSI != rssi) {
_telemetryLRSSI = rssi;
emit telemetryLRSSIChanged(_telemetryLRSSI);
}
if(_telemetryRRSSI != remrssi) {
_telemetryRRSSI = remrssi;
emit telemetryRRSSIChanged(_telemetryRRSSI);
}
if(_telemetryRXErrors != rxerrors) {
_telemetryRXErrors = rxerrors;
emit telemetryRXErrorsChanged(_telemetryRXErrors);
}
if(_telemetryFixed != fixed) {
_telemetryFixed = fixed;
emit telemetryFixedChanged(_telemetryFixed);
}
if(_telemetryTXBuffer != txbuf) {
_telemetryTXBuffer = txbuf;
emit telemetryTXBufferChanged(_telemetryTXBuffer);
}
if(_telemetryLNoise != noise) {
_telemetryLNoise = noise;
emit telemetryLNoiseChanged(_telemetryLNoise);
}
if(_telemetryRNoise != remnoise) {
_telemetryRNoise = remnoise;
emit telemetryRNoiseChanged(_telemetryRNoise);
}
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
/**
* @file
* @brief QGC Main Tool Bar
* @author Gus Grubba <mavlink@grubba.com>
*/
#ifndef MainToolBarController_H
#define MainToolBarController_H
#include <QObject>
#include "Vehicle.h"
#include "UASMessageView.h"
class MainToolBarController : public QObject
{
Q_OBJECT
public:
MainToolBarController(QObject* parent = NULL);
~MainToolBarController();
Q_PROPERTY(int telemetryRRSSI READ telemetryRRSSI NOTIFY telemetryRRSSIChanged)
Q_PROPERTY(int telemetryLRSSI READ telemetryLRSSI NOTIFY telemetryLRSSIChanged)
Q_PROPERTY(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged)
Q_PROPERTY(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged)
Q_PROPERTY(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged)
Q_PROPERTY(unsigned int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged)
Q_PROPERTY(unsigned int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged)
int telemetryRRSSI () { return _telemetryRRSSI; }
int telemetryLRSSI () { return _telemetryLRSSI; }
unsigned int telemetryRXErrors () { return _telemetryRXErrors; }
unsigned int telemetryFixed () { return _telemetryFixed; }
unsigned int telemetryTXBuffer () { return _telemetryTXBuffer; }
unsigned int telemetryLNoise () { return _telemetryLNoise; }
unsigned int telemetryRNoise () { return _telemetryRNoise; }
signals:
void telemetryRRSSIChanged (int value);
void telemetryLRSSIChanged (int value);
void telemetryRXErrorsChanged (unsigned int value);
void telemetryFixedChanged (unsigned int value);
void telemetryTXBufferChanged (unsigned int value);
void telemetryLNoiseChanged (unsigned int value);
void telemetryRNoiseChanged (unsigned int value);
private slots:
void _activeVehicleChanged (Vehicle* vehicle);
void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
private:
Vehicle* _vehicle;
UASInterface* _mav;
double _remoteRSSIstore;
int _telemetryRRSSI;
int _telemetryLRSSI;
uint32_t _telemetryRXErrors;
uint32_t _telemetryFixed;
uint32_t _telemetryTXBuffer;
uint32_t _telemetryLNoise;
uint32_t _telemetryRNoise;
};
#endif // MainToolBarController_H
......@@ -273,19 +273,19 @@ Item {
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel { text: qsTr("Local RSSI:") }
QGCLabel { text: _controller.telemetryLRSSI + " dBm" }
QGCLabel { text: _activeVehicle.telemetryLRSSI + " dBm" }
QGCLabel { text: qsTr("Remote RSSI:") }
QGCLabel { text: _controller.telemetryRRSSI + " dBm" }
QGCLabel { text: _activeVehicle.telemetryRRSSI + " dBm" }
QGCLabel { text: qsTr("RX Errors:") }
QGCLabel { text: _controller.telemetryRXErrors }
QGCLabel { text: _activeVehicle.telemetryRXErrors }
QGCLabel { text: qsTr("Errors Fixed:") }
QGCLabel { text: _controller.telemetryFixed }
QGCLabel { text: _activeVehicle.telemetryFixed }
QGCLabel { text: qsTr("TX Buffer:") }
QGCLabel { text: _controller.telemetryTXBuffer }
QGCLabel { text: _activeVehicle.telemetryTXBuffer }
QGCLabel { text: qsTr("Local Noise:") }
QGCLabel { text: _controller.telemetryLNoise }
QGCLabel { text: _activeVehicle.telemetryLNoise }
QGCLabel { text: qsTr("Remote Noise:") }
QGCLabel { text: _controller.telemetryRNoise }
QGCLabel { text: _activeVehicle.telemetryRNoise }
}
}
......@@ -440,7 +440,7 @@ Item {
source: "/qmlimages/TelemRSSI.svg"
fillMode: Image.PreserveAspectFit
color: qgcPal.buttonText
visible: _controller.telemetryLRSSI < 0
visible: _activeVehicle ? (_activeVehicle.telemetryLRSSI < 0) : false
MouseArea {
anchors.fill: parent
......
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