Commit 2b206c00 authored by Don Gagne's avatar Don Gagne

New toolbar dropdown support

- select active vehicle
- arm/disarm
- select flight mode
parent 62d95365
...@@ -39,7 +39,6 @@ AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : ...@@ -39,7 +39,6 @@ AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
Q_ASSERT(vehicle); Q_ASSERT(vehicle);
connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected); connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(_vehicle->uas(), &UASInterface::armingChanged, this, &AutoPilotPlugin::armedChanged);
connect(this, &AutoPilotPlugin::pluginReadyChanged, this, &AutoPilotPlugin::_pluginReadyChanged); connect(this, &AutoPilotPlugin::pluginReadyChanged, this, &AutoPilotPlugin::_pluginReadyChanged);
} }
...@@ -176,8 +175,3 @@ QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) ...@@ -176,8 +175,3 @@ QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{ {
return _getParameterLoader()->readParametersFromStream(stream); return _getParameterLoader()->readParametersFromStream(stream);
} }
bool AutoPilotPlugin::armed(void)
{
return _vehicle->uas()->isArmed();
}
...@@ -63,8 +63,6 @@ public: ...@@ -63,8 +63,6 @@ public:
/// false: One or more vehicle components require setup /// false: One or more vehicle components require setup
Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged) Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged)
Q_PROPERTY(bool armed READ armed NOTIFY armedChanged)
/// Reset all parameters to their default values /// Reset all parameters to their default values
Q_INVOKABLE void resetAllParametersToDefaults(void); Q_INVOKABLE void resetAllParametersToDefaults(void);
...@@ -117,7 +115,6 @@ public: ...@@ -117,7 +115,6 @@ public:
// Property accessors // Property accessors
bool pluginReady(void) { return _pluginReady; } bool pluginReady(void) { return _pluginReady; }
bool setupComplete(void); bool setupComplete(void);
bool armed(void);
Vehicle* vehicle(void) { return _vehicle; } Vehicle* vehicle(void) { return _vehicle; }
...@@ -125,7 +122,6 @@ signals: ...@@ -125,7 +122,6 @@ signals:
void pluginReadyChanged(bool pluginReady); void pluginReadyChanged(bool pluginReady);
void setupCompleteChanged(bool setupComplete); void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value); void parameterListProgress(float value);
void armedChanged(bool armed);
protected: protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin /// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
......
...@@ -115,7 +115,6 @@ QUrl SensorsComponent::summaryQmlSource(void) const ...@@ -115,7 +115,6 @@ QUrl SensorsComponent::summaryQmlSource(void) const
{ {
QString summaryQml; QString summaryQml;
qDebug() << _uas->getSystemType();
if (_uas->getSystemType() == MAV_TYPE_FIXED_WING || if (_uas->getSystemType() == MAV_TYPE_FIXED_WING ||
_uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR || _uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
_uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR || _uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR ||
......
...@@ -191,5 +191,5 @@ void PX4FirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) ...@@ -191,5 +191,5 @@ void PX4FirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
bool PX4FirmwarePlugin::isCapable(FirmwareCapabilities capabilities) bool PX4FirmwarePlugin::isCapable(FirmwareCapabilities capabilities)
{ {
return capabilities == MavCmdPreflightStorageCapability; return capabilities && (MavCmdPreflightStorageCapability | SetFlightModeCapability);
} }
...@@ -42,7 +42,7 @@ QGC_LOGGING_CATEGORY(JoystickValuesLog, "JoystickValuesLog") ...@@ -42,7 +42,7 @@ QGC_LOGGING_CATEGORY(JoystickValuesLog, "JoystickValuesLog")
const char* Joystick::_settingsGroup = "Joysticks"; const char* Joystick::_settingsGroup = "Joysticks";
const char* Joystick::_calibratedSettingsKey = "Calibrated"; const char* Joystick::_calibratedSettingsKey = "Calibrated";
const char* Joystick::_buttonActionSettingsKey = "ButtonAction%1"; const char* Joystick::_buttonActionSettingsKey = "ButtonActionName%1";
const char* Joystick::_throttleModeSettingsKey = "ThrottleMode"; const char* Joystick::_throttleModeSettingsKey = "ThrottleMode";
const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = { const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
...@@ -144,10 +144,8 @@ void Joystick::_loadSettings(void) ...@@ -144,10 +144,8 @@ void Joystick::_loadSettings(void)
} }
for (int button=0; button<_cButtons; button++) { for (int button=0; button<_cButtons; button++) {
_rgButtonActions[button] = settings.value(QString(_buttonActionSettingsKey).arg(button), -1).toInt(&convertOk); _rgButtonActions[button] = settings.value(QString(_buttonActionSettingsKey).arg(button), QString()).toString();
badSettings |= !convertOk; qCDebug(JoystickLog) << "_loadSettings button:action" << button << _rgButtonActions[button];
qCDebug(JoystickLog) << "_loadSettings button:action:badsettings" << button << _rgButtonActions[button] << badSettings;
} }
if (badSettings) { if (badSettings) {
...@@ -322,10 +320,9 @@ void Joystick::run(void) ...@@ -322,10 +320,9 @@ void Joystick::run(void)
if (buttonIndex >= reservedButtonCount) { if (buttonIndex >= reservedButtonCount) {
// Button is above firmware reserved set // Button is above firmware reserved set
int buttonAction =_rgButtonActions[buttonIndex]; QString buttonAction =_rgButtonActions[buttonIndex];
if (buttonAction != -1) { if (!buttonAction.isEmpty()) {
qCDebug(JoystickLog) << "buttonActionTriggered" << buttonAction; _buttonAction(buttonAction);
emit buttonActionTriggered(buttonAction);
} }
} }
} }
...@@ -369,7 +366,8 @@ void Joystick::startPolling(Vehicle* vehicle) ...@@ -369,7 +366,8 @@ void Joystick::startPolling(Vehicle* vehicle)
UAS* uas = _activeVehicle->uas(); UAS* uas = _activeVehicle->uas();
connect(this, &Joystick::manualControl, uas, &UAS::setExternalControlSetpoint); connect(this, &Joystick::manualControl, uas, &UAS::setExternalControlSetpoint);
connect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction); // FIXME: ****
//connect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
_exitThread = false; _exitThread = false;
start(); start();
...@@ -382,7 +380,8 @@ void Joystick::stopPolling(void) ...@@ -382,7 +380,8 @@ void Joystick::stopPolling(void)
UAS* uas = _activeVehicle->uas(); UAS* uas = _activeVehicle->uas();
disconnect(this, &Joystick::manualControl, uas, &UAS::setExternalControlSetpoint); disconnect(this, &Joystick::manualControl, uas, &UAS::setExternalControlSetpoint);
disconnect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction); // FIXME: ****
//disconnect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
_exitThread = true; _exitThread = true;
} }
...@@ -435,27 +434,27 @@ int Joystick::getFunctionAxis(AxisFunction_t function) ...@@ -435,27 +434,27 @@ int Joystick::getFunctionAxis(AxisFunction_t function)
QStringList Joystick::actions(void) QStringList Joystick::actions(void)
{ {
QStringList list; QStringList list;
foreach(QAction* action, MultiVehicleManager::instance()->activeVehicle()->uas()->getActions()) { list << "Arm" << "Disarm";
list += action->text();
}
return list; return list;
} }
void Joystick::setButtonAction(int button, int action) void Joystick::setButtonAction(int button, const QString& action)
{ {
if (button < 0 || button > _cButtons) { if (button < 0 || button > _cButtons) {
qCWarning(JoystickLog) << "Invalid button index" << button; qCWarning(JoystickLog) << "Invalid button index" << button;
return; return;
} }
qDebug() << "setButtonAction" << action;
_rgButtonActions[button] = action; _rgButtonActions[button] = action;
_saveSettings(); _saveSettings();
emit buttonActionsChanged(buttonActions()); emit buttonActionsChanged(buttonActions());
} }
int Joystick::getButtonAction(int button) QString Joystick::getButtonAction(int button)
{ {
if (button < 0 || button > _cButtons) { if (button < 0 || button > _cButtons) {
qCWarning(JoystickLog) << "Invalid button index" << button; qCWarning(JoystickLog) << "Invalid button index" << button;
...@@ -512,9 +511,6 @@ void Joystick::stopCalibrationMode(CalibrationMode_t mode) ...@@ -512,9 +511,6 @@ void Joystick::stopCalibrationMode(CalibrationMode_t mode)
if (mode == CalibrationModeOff) { if (mode == CalibrationModeOff) {
qWarning() << "Incorrect mode: CalibrationModeOff"; qWarning() << "Incorrect mode: CalibrationModeOff";
return; return;
} else if (mode != _calibrationMode) {
qWarning() << "Incorrect mode sequence request:active" << mode << _calibrationMode;
return;
} }
if (mode == CalibrationModeCalibrating) { if (mode == CalibrationModeCalibrating) {
...@@ -527,4 +523,15 @@ void Joystick::stopCalibrationMode(CalibrationMode_t mode) ...@@ -527,4 +523,15 @@ void Joystick::stopCalibrationMode(CalibrationMode_t mode)
} }
} }
void Joystick::_buttonAction(const QString& action)
{
if (action == "Arm") {
_activeVehicle->setArmed(true);
} else if (action == "Disarm") {
_activeVehicle->setArmed(false);
} else {
qCDebug(JoystickLog) << "_buttonAction unknown action:" << action;
}
}
#endif // __mobile__ #endif // __mobile__
...@@ -73,8 +73,8 @@ public: ...@@ -73,8 +73,8 @@ public:
Q_PROPERTY(QStringList actions READ actions CONSTANT) Q_PROPERTY(QStringList actions READ actions CONSTANT)
Q_PROPERTY(QVariantList buttonActions READ buttonActions NOTIFY buttonActionsChanged) Q_PROPERTY(QVariantList buttonActions READ buttonActions NOTIFY buttonActionsChanged)
Q_INVOKABLE void setButtonAction(int button, int action); Q_INVOKABLE void setButtonAction(int button, const QString& action);
Q_INVOKABLE int getButtonAction(int button); Q_INVOKABLE QString getButtonAction(int button);
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged) Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged)
...@@ -135,6 +135,7 @@ private: ...@@ -135,6 +135,7 @@ private:
void _saveSettings(void); void _saveSettings(void);
void _loadSettings(void); void _loadSettings(void);
float _adjustRange(int value, Calibration_t calibration); float _adjustRange(int value, Calibration_t calibration);
void _buttonAction(const QString& action);
// Override from QThread // Override from QThread
virtual void run(void); virtual void run(void);
...@@ -158,7 +159,7 @@ private: ...@@ -158,7 +159,7 @@ private:
static const int _cButtons = 12; static const int _cButtons = 12;
bool _rgButtonValues[_cButtons]; bool _rgButtonValues[_cButtons];
int _rgButtonActions[_cButtons]; QString _rgButtonActions[_cButtons];
quint16 _lastButtonBits; quint16 _lastButtonBits;
ThrottleMode_t _throttleMode; ThrottleMode_t _throttleMode;
......
...@@ -27,6 +27,7 @@ ...@@ -27,6 +27,7 @@
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include <QDebug> #include <QDebug>
#include <QQmlEngine>
const int QmlObjectListModel::ObjectRole = Qt::UserRole; const int QmlObjectListModel::ObjectRole = Qt::UserRole;
const int QmlObjectListModel::TextRole = Qt::UserRole + 1; const int QmlObjectListModel::TextRole = Qt::UserRole + 1;
...@@ -156,6 +157,8 @@ void QmlObjectListModel::insert(int i, QObject* object) ...@@ -156,6 +157,8 @@ void QmlObjectListModel::insert(int i, QObject* object)
qWarning() << "Invalid index index:count" << i << _objectList.count(); qWarning() << "Invalid index index:count" << i << _objectList.count();
} }
QQmlEngine::setObjectOwnership(object, QQmlEngine::CppOwnership);
_objectList.insert(i, object); _objectList.insert(i, object);
insertRows(i, 1); insertRows(i, 1);
} }
......
...@@ -58,7 +58,7 @@ public: ...@@ -58,7 +58,7 @@ public:
/// @return true: continue further processing of this message, false: disregard this message /// @return true: continue further processing of this message, false: disregard this message
bool notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat); bool notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat);
Vehicle* getVehicleById(int vehicleId); Q_INVOKABLE Vehicle* getVehicleById(int vehicleId);
void setHomePositionForAllVehicles(double lat, double lon, double alt); void setHomePositionForAllVehicles(double lat, double lon, double alt);
......
...@@ -78,7 +78,6 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -78,7 +78,6 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
, _batteryVoltage(0.0) , _batteryVoltage(0.0)
, _batteryPercent(0.0) , _batteryPercent(0.0)
, _batteryConsumed(-1.0) , _batteryConsumed(-1.0)
, _systemArmed(false)
, _currentHeartbeatTimeout(0) , _currentHeartbeatTimeout(0)
, _waypointDistance(0.0) , _waypointDistance(0.0)
, _currentWaypoint(0) , _currentWaypoint(0)
...@@ -86,13 +85,18 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -86,13 +85,18 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
, _satelliteLock(0) , _satelliteLock(0)
, _wpm(NULL) , _wpm(NULL)
, _updateCount(0) , _updateCount(0)
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
{ {
_addLink(link); _addLink(link);
connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived); _mavlink = MAVLinkProtocol::instance();
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(this, &Vehicle::_sendMessageOnThread, this, &Vehicle::_sendMessage, Qt::QueuedConnection); connect(this, &Vehicle::_sendMessageOnThread, this, &Vehicle::_sendMessage, Qt::QueuedConnection);
_uas = new UAS(MAVLinkProtocol::instance(), this); _uas = new UAS(_mavlink, this);
setLatitude(_uas->getLatitude()); setLatitude(_uas->getLatitude());
setLongitude(_uas->getLongitude()); setLongitude(_uas->getLongitude());
...@@ -125,12 +129,10 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -125,12 +129,10 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
connect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); connect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64)));
connect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); connect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double)));
connect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString))); connect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString)));
connect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool)));
connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData); connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData);
connect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout); connect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout);
connect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining); connect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining);
connect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged); connect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged);
connect(_mav, &UASInterface::modeChanged, this, &Vehicle::_updateMode);
connect(_mav, &UASInterface::nameChanged, this, &Vehicle::_updateName); connect(_mav, &UASInterface::nameChanged, this, &Vehicle::_updateName);
connect(_mav, &UASInterface::systemTypeSet, this, &Vehicle::_setSystemType); connect(_mav, &UASInterface::systemTypeSet, this, &Vehicle::_setSystemType);
connect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc); connect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc);
...@@ -148,7 +150,6 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -148,7 +150,6 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
connect(pUas, &UAS::satelliteCountChanged, this, &Vehicle::_setSatelliteCount); connect(pUas, &UAS::satelliteCountChanged, this, &Vehicle::_setSatelliteCount);
} }
_setSystemType(_mav, _mav->getSystemType()); _setSystemType(_mav, _mav->getSystemType());
_updateArmingState(_mav->isArmed());
_waypointViewOnlyListChanged(); _waypointViewOnlyListChanged();
...@@ -170,12 +171,10 @@ Vehicle::~Vehicle() ...@@ -170,12 +171,10 @@ Vehicle::~Vehicle()
disconnect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); disconnect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64)));
disconnect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); disconnect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double)));
disconnect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString))); disconnect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString)));
disconnect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool)));
disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData); disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData);
disconnect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout); disconnect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout);
disconnect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining); disconnect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining);
disconnect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged); disconnect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged);
disconnect(_mav, &UASInterface::modeChanged, this, &Vehicle::_updateMode);
disconnect(_mav, &UASInterface::nameChanged, this, &Vehicle::_updateName); disconnect(_mav, &UASInterface::nameChanged, this, &Vehicle::_updateName);
disconnect(_mav, &UASInterface::systemTypeSet, this, &Vehicle::_setSystemType); disconnect(_mav, &UASInterface::systemTypeSet, this, &Vehicle::_setSystemType);
disconnect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc); disconnect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc);
...@@ -204,18 +203,13 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -204,18 +203,13 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
// Give the plugin a change to adjust the message contents // Give the plugin a change to adjust the message contents
_firmwarePlugin->adjustMavlinkMessage(&message); _firmwarePlugin->adjustMavlinkMessage(&message);
if (message.msgid == MAVLINK_MSG_ID_HOME_POSITION) { switch (message.msgid) {
mavlink_home_position_t homePos; case MAVLINK_MSG_ID_HOME_POSITION:
_handleHomePosition(message);
mavlink_msg_home_position_decode(&message, &homePos); break;
case MAVLINK_MSG_ID_HEARTBEAT:
_homePosition.setLatitude(homePos.latitude / 10000000.0); _handleHeartbeat(message);
_homePosition.setLongitude(homePos.longitude / 10000000.0); break;
_homePosition.setAltitude(homePos.altitude / 1000.0);
_homePositionAvailable = true;
emit homePositionAvailableChanged(true);
emit homePositionChanged(_homePosition);
} }
emit mavlinkMessageReceived(message); emit mavlinkMessageReceived(message);
...@@ -223,6 +217,41 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -223,6 +217,41 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
_uas->receiveMessage(message); _uas->receiveMessage(message);
} }
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
mavlink_home_position_t homePos;
mavlink_msg_home_position_decode(&message, &homePos);
_homePosition.setLatitude(homePos.latitude / 10000000.0);
_homePosition.setLongitude(homePos.longitude / 10000000.0);
_homePosition.setAltitude(homePos.altitude / 1000.0);
_homePositionAvailable = true;
emit homePositionAvailableChanged(true);
emit homePositionChanged(_homePosition);
}
void Vehicle::_handleHeartbeat(mavlink_message_t& message)
{
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat);
bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
if (_armed != newArmed) {
_armed = newArmed;
emit armedChanged(_armed);
}
if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
_base_mode = heartbeat.base_mode;
_custom_mode = heartbeat.custom_mode;
emit flightModeChanged(flightMode());
}
}
bool Vehicle::_containsLink(LinkInterface* link) bool Vehicle::_containsLink(LinkInterface* link)
{ {
foreach (SharedLinkInterface sharedLink, _links) { foreach (SharedLinkInterface sharedLink, _links) {
...@@ -273,7 +302,7 @@ void Vehicle::_sendMessage(mavlink_message_t message) ...@@ -273,7 +302,7 @@ void Vehicle::_sendMessage(mavlink_message_t message)
Q_ASSERT(link); Q_ASSERT(link);
if (link->isConnected()) { if (link->isConnected()) {
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); MAVLinkProtocol* mavlink = _mavlink;
// Give the plugin a chance to adjust // Give the plugin a chance to adjust
_firmwarePlugin->adjustMavlinkMessage(&message); _firmwarePlugin->adjustMavlinkMessage(&message);
...@@ -542,14 +571,6 @@ QString Vehicle::getMavIconColor() ...@@ -542,14 +571,6 @@ QString Vehicle::getMavIconColor()
return QString("black"); return QString("black");
} }
void Vehicle::_updateArmingState(bool armed)
{
if(_systemArmed != armed) {
_systemArmed = armed;
emit systemArmedChanged();
}
}
void Vehicle::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int) void Vehicle::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int)
{ {
...@@ -586,19 +607,6 @@ void Vehicle::_updateState(UASInterface*, QString name, QString) ...@@ -586,19 +607,6 @@ void Vehicle::_updateState(UASInterface*, QString name, QString)
} }
} }
void Vehicle::_updateMode(int, QString name, QString)
{
if (name.size()) {
QString shortMode = name;
shortMode = shortMode.replace("D|", "");
shortMode = shortMode.replace("A|", "");
if (_currentMode != shortMode) {
_currentMode = shortMode;
emit currentModeChanged();
}
}
}
void Vehicle::_updateName(const QString& name) void Vehicle::_updateName(const QString& name)
{ {
if (_systemName != name) { if (_systemName != name) {
...@@ -974,3 +982,79 @@ QGeoCoordinate Vehicle::homePosition(void) ...@@ -974,3 +982,79 @@ QGeoCoordinate Vehicle::homePosition(void)
return _homePosition; return _homePosition;
} }
void Vehicle::setArmed(bool armed)
{
// We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = (uint16_t)MAV_CMD_COMPONENT_ARM_DISARM;
cmd.confirmation = 0;
cmd.param1 = armed ? 1.0f : 0.0f;
cmd.param2 = 0.0f;
cmd.param3 = 0.0f;
cmd.param4 = 0.0f;
cmd.param5 = 0.0f;
cmd.param6 = 0.0f;
cmd.param7 = 0.0f;
cmd.target_system = id();
cmd.target_component = 0;
mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg);
}
bool Vehicle::flightModeSetAvailable(void)
{
return _firmwarePlugin->isCapable(FirmwarePlugin::SetFlightModeCapability);
}
QStringList Vehicle::flightModes(void)
{
return _firmwarePlugin->flightModes();
}
QString Vehicle::flightMode(void)
{
return _firmwarePlugin->flightMode(_base_mode, _custom_mode);
}
void Vehicle::setFlightMode(const QString& flightMode)
{
uint8_t base_mode;
uint32_t custom_mode;
if (_firmwarePlugin->setFlightMode(flightMode, &base_mode, &custom_mode)) {
// setFlightMode will only set MAV_MODE_FLAG_CUSTOM_MODE_ENABLED in base_mode, we need to move back in the existing
// states.
uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE;
newBaseMode |= base_mode;
mavlink_message_t msg;
mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, custom_mode);
sendMessage(msg);
} else {
qCWarning(VehicleLog) << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
}
}
bool Vehicle::hilMode(void)
{
return _base_mode & MAV_MODE_FLAG_HIL_ENABLED;
}
void Vehicle::setHilMode(bool hilMode)
{
mavlink_message_t msg;
uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_HIL;
if (hilMode) {
newBaseMode |= MAV_MODE_FLAG_HIL_ENABLED;
}
mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, _custom_mode);
sendMessage(msg);
}
...@@ -35,6 +35,7 @@ ...@@ -35,6 +35,7 @@
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "MissionItem.h" #include "MissionItem.h"
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include "MAVLinkProtocol.h"
class UAS; class UAS;
class UASInterface; class UASInterface;
...@@ -62,6 +63,14 @@ public: ...@@ -62,6 +63,14 @@ public:
Q_PROPERTY(bool homePositionAvailable READ homePositionAvailable NOTIFY homePositionAvailableChanged) Q_PROPERTY(bool homePositionAvailable READ homePositionAvailable NOTIFY homePositionAvailableChanged)
Q_PROPERTY(QGeoCoordinate homePosition READ homePosition NOTIFY homePositionChanged) Q_PROPERTY(QGeoCoordinate homePosition READ homePosition NOTIFY homePositionChanged)
Q_PROPERTY(bool armed READ armed WRITE setArmed NOTIFY armedChanged)
Q_PROPERTY(bool flightModeSetAvailable READ flightModeSetAvailable CONSTANT)
Q_PROPERTY(QStringList flightModes READ flightModes CONSTANT)
Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged)
Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged)
Q_INVOKABLE QString getMavIconColor(); Q_INVOKABLE QString getMavIconColor();
//-- System Messages //-- System Messages
...@@ -87,8 +96,6 @@ public: ...@@ -87,8 +96,6 @@ public:
Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged)
Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged)
Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged) Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged)
Q_PROPERTY(bool systemArmed READ systemArmed NOTIFY systemArmedChanged)
Q_PROPERTY(QString currentMode READ currentMode NOTIFY currentModeChanged)
Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged) Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged)
Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged) Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged)
Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged) Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged)
...@@ -160,6 +167,17 @@ public: ...@@ -160,6 +167,17 @@ public:
bool homePositionAvailable(void); bool homePositionAvailable(void);
QGeoCoordinate homePosition(void); QGeoCoordinate homePosition(void);
bool armed(void) { return _armed; }
void setArmed(bool armed);
bool flightModeSetAvailable(void);
QStringList flightModes(void);
QString flightMode(void);
void setFlightMode(const QString& flightMode);
bool hilMode(void);
void setHilMode(bool hilMode);
typedef enum { typedef enum {
MessageNone, MessageNone,
MessageNormal, MessageNormal,
...@@ -206,8 +224,6 @@ public: ...@@ -206,8 +224,6 @@ public:
double batteryVoltage () { return _batteryVoltage; } double batteryVoltage () { return _batteryVoltage; }
double batteryPercent () { return _batteryPercent; } double batteryPercent () { return _batteryPercent; }
double batteryConsumed () { return _batteryConsumed; } double batteryConsumed () { return _batteryConsumed; }
bool systemArmed () { return _systemArmed; }
QString currentMode () { return _currentMode; }
QString systemPixmap () { return _systemPixmap; } QString systemPixmap () { return _systemPixmap; }
QString currentState () { return _currentState; } QString currentState () { return _currentState; }
QString systemName () { return _systemName; } QString systemName () { return _systemName; }
...@@ -229,6 +245,9 @@ signals: ...@@ -229,6 +245,9 @@ signals:
void mavlinkMessageReceived(const mavlink_message_t& message); void mavlinkMessageReceived(const mavlink_message_t& message);
void homePositionAvailableChanged(bool homePositionAvailable); void homePositionAvailableChanged(bool homePositionAvailable);
void homePositionChanged(const QGeoCoordinate& homePosition); void homePositionChanged(const QGeoCoordinate& homePosition);
void armedChanged(bool armed);
void flightModeChanged(const QString& flightMode);
void hilModeChanged(bool hilMode);
/// Used internally to move sendMessage call to main thread /// Used internally to move sendMessage call to main thread
void _sendMessageOnThread(mavlink_message_t message); void _sendMessageOnThread(mavlink_message_t message);
...@@ -251,9 +270,7 @@ signals: ...@@ -251,9 +270,7 @@ signals:
void batteryVoltageChanged (); void batteryVoltageChanged ();
void batteryPercentChanged (); void batteryPercentChanged ();
void batteryConsumedChanged (); void batteryConsumedChanged ();
void systemArmedChanged ();
void heartbeatTimeoutChanged(); void heartbeatTimeoutChanged();
void currentModeChanged ();
void currentConfigChanged (); void currentConfigChanged ();
void systemPixmapChanged (); void systemPixmapChanged ();
void satelliteCountChanged (); void satelliteCountChanged ();
...@@ -282,9 +299,7 @@ private slots: ...@@ -282,9 +299,7 @@ private slots:
void _checkUpdate (); void _checkUpdate ();
void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int);
void _updateBatteryConsumedChanged (UASInterface*, double current_consumed); void _updateBatteryConsumedChanged (UASInterface*, double current_consumed);
void _updateArmingState (bool armed);
void _updateState (UASInterface* system, QString name, QString description); void _updateState (UASInterface* system, QString name, QString description);
void _updateMode (int system, QString name, QString description);
void _updateName (const QString& name); void _updateName (const QString& name);
void _setSystemType (UASInterface* uas, unsigned int systemType); void _setSystemType (UASInterface* uas, unsigned int systemType);
void _heartbeatTimeout (bool timeout, unsigned int ms); void _heartbeatTimeout (bool timeout, unsigned int ms);
...@@ -301,7 +316,9 @@ private: ...@@ -301,7 +316,9 @@ private:
void _loadSettings(void); void _loadSettings(void);
void _saveSettings(void); void _saveSettings(void);
void _startJoystick(bool start); void _startJoystick(bool start);
void _handleHomePosition(mavlink_message_t& message);
void _handleHeartbeat(mavlink_message_t& message);
bool _isAirplane (); bool _isAirplane ();
void _addChange (int id); void _addChange (int id);
float _oneDecimal (float value); float _oneDecimal (float value);
...@@ -313,6 +330,7 @@ private: ...@@ -313,6 +330,7 @@ private:
MAV_AUTOPILOT _firmwareType; MAV_AUTOPILOT _firmwareType;
FirmwarePlugin* _firmwarePlugin; FirmwarePlugin* _firmwarePlugin;
AutoPilotPlugin* _autopilotPlugin; AutoPilotPlugin* _autopilotPlugin;
MAVLinkProtocol* _mavlink;
/// List of all links associated with this vehicle. We keep SharedLinkInterface objects /// List of all links associated with this vehicle. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads. /// which are QSharedPointer's in order to maintain reference counts across threads.
...@@ -357,9 +375,7 @@ private: ...@@ -357,9 +375,7 @@ private:
double _batteryVoltage; double _batteryVoltage;
double _batteryPercent; double _batteryPercent;
double _batteryConsumed; double _batteryConsumed;
bool _systemArmed;
QString _currentState; QString _currentState;
QString _currentMode;
QString _systemName; QString _systemName;
QString _systemPixmap; QString _systemPixmap;
unsigned int _currentHeartbeatTimeout; unsigned int _currentHeartbeatTimeout;
...@@ -373,6 +389,10 @@ private: ...@@ -373,6 +389,10 @@ private:
MissionManager* _missionManager; MissionManager* _missionManager;
QmlObjectListModel _missionItems; QmlObjectListModel _missionItems;
bool _armed; ///< true: vehicle is armed
uint8_t _base_mode; ///< base_mode from HEARTBEAT
uint32_t _custom_mode; ///< custom_mode from HEARTBEAT
static const char* _settingsGroup; static const char* _settingsGroup;
static const char* _joystickModeSettingsKey; static const char* _joystickModeSettingsKey;
static const char* _joystickEnabledSettingsKey; static const char* _joystickEnabledSettingsKey;
......
...@@ -482,9 +482,9 @@ QGCView { ...@@ -482,9 +482,9 @@ QGCView {
QGCCheckBox { QGCCheckBox {
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
checked: _activeJoystick.buttonActions[modelData] != -1 checked: _activeJoystick.buttonActions[modelData] != ""
onClicked: _activeJoystick.setButtonAction(modelData, checked ? buttonActionCombo.currentIndex : -1) onClicked: _activeJoystick.setButtonAction(modelData, checked ? buttonActionCombo.textAt(buttonActionCombo.currentIndex) : "")
} }
Rectangle { Rectangle {
...@@ -509,9 +509,9 @@ QGCView { ...@@ -509,9 +509,9 @@ QGCView {
id: buttonActionCombo id: buttonActionCombo
width: ScreenTools.defaultFontPixelWidth * 20 width: ScreenTools.defaultFontPixelWidth * 20
model: _activeJoystick.actions model: _activeJoystick.actions
currentIndex: _activeJoystick.buttonActions[modelData]
onActivated: _activeJoystick.setButtonAction(modelData, index) onActivated: _activeJoystick.setButtonAction(modelData, textAt(index))
Component.onCompleted: currentIndex = find(_activeJoystick.buttonActions[modelData])
} }
} }
} // Repeater } // Repeater
......
...@@ -63,7 +63,7 @@ Rectangle { ...@@ -63,7 +63,7 @@ Rectangle {
function showFirmwarePanel() function showFirmwarePanel()
{ {
if (!ScreenTools.isMobile) { if (!ScreenTools.isMobile) {
if (multiVehicleManager.activeVehicleAvailable && multiVehicleManager.activeVehicle.autopilot.armed) { if (multiVehicleManager.activeVehicleAvailable && multiVehicleManager.activeVehicle.armed) {
messagePanelText = armedVehicleText messagePanelText = armedVehicleText
panelLoader.sourceComponent = messagePanelComponent panelLoader.sourceComponent = messagePanelComponent
} else { } else {
...@@ -74,7 +74,7 @@ Rectangle { ...@@ -74,7 +74,7 @@ Rectangle {
function showJoystickPanel() function showJoystickPanel()
{ {
if (multiVehicleManager.activeVehicleAvailable && multiVehicleManager.activeVehicle.autopilot.armed) { if (multiVehicleManager.activeVehicleAvailable && multiVehicleManager.activeVehicle.armed) {
messagePanelText = armedVehicleText messagePanelText = armedVehicleText
panelLoader.sourceComponent = messagePanelComponent panelLoader.sourceComponent = messagePanelComponent
} else { } else {
...@@ -89,7 +89,7 @@ Rectangle { ...@@ -89,7 +89,7 @@ Rectangle {
function showVehicleComponentPanel(vehicleComponent) function showVehicleComponentPanel(vehicleComponent)
{ {
if (multiVehicleManager.activeVehicle.autopilot.armed) { if (multiVehicleManager.activeVehicle.armed) {
messagePanelText = armedVehicleText messagePanelText = armedVehicleText
panelLoader.sourceComponent = messagePanelComponent panelLoader.sourceComponent = messagePanelComponent
} else { } else {
......
...@@ -338,7 +338,6 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes) ...@@ -338,7 +338,6 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
break; break;
default: default:
qDebug() << "MockLink: Unhandled mavlink message, id:" << msg.msgid;
break; break;
} }
} }
......
...@@ -150,13 +150,10 @@ void MavlinkLogTest::_connectLogWorker(bool arm) ...@@ -150,13 +150,10 @@ void MavlinkLogTest::_connectLogWorker(bool arm)
QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*))); QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*)));
QCOMPARE(spyVehicle.wait(5000), true); QCOMPARE(spyVehicle.wait(5000), true);
UAS* uas = MultiVehicleManager::instance()->activeUas();
QVERIFY(uas);
QDir logSaveDir; QDir logSaveDir;
if (arm) { if (arm) {
uas->armSystem(); MultiVehicleManager::instance()->activeVehicle()->setArmed(true);
QTest::qWait(1500); // Wait long enough for heartbeat to come through QTest::qWait(1500); // Wait long enough for heartbeat to come through
// On Disconnect: We should get a getSaveFileName dialog. // On Disconnect: We should get a getSaveFileName dialog.
......
...@@ -86,8 +86,6 @@ This file is part of the QGROUNDCONTROL project ...@@ -86,8 +86,6 @@ This file is part of the QGROUNDCONTROL project
/// The key under which the Main Window settings are saved /// The key under which the Main Window settings are saved
const char* MAIN_SETTINGS_GROUP = "QGC_MAINWINDOW"; const char* MAIN_SETTINGS_GROUP = "QGC_MAINWINDOW";
const char* MainWindow::_uasControlDockWidgetName = "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET";
const char* MainWindow::_uasListDockWidgetName = "UNMANNED_SYSTEM_LIST_DOCKWIDGET";
const char* MainWindow::_waypointsDockWidgetName = "WAYPOINT_LIST_DOCKWIDGET"; const char* MainWindow::_waypointsDockWidgetName = "WAYPOINT_LIST_DOCKWIDGET";
const char* MainWindow::_mavlinkDockWidgetName = "MAVLINK_INSPECTOR_DOCKWIDGET"; const char* MainWindow::_mavlinkDockWidgetName = "MAVLINK_INSPECTOR_DOCKWIDGET";
const char* MainWindow::_customCommandWidgetName = "CUSTOM_COMMAND_DOCKWIDGET"; const char* MainWindow::_customCommandWidgetName = "CUSTOM_COMMAND_DOCKWIDGET";
...@@ -388,8 +386,6 @@ void MainWindow::_buildCommonWidgets(void) ...@@ -388,8 +386,6 @@ void MainWindow::_buildCommonWidgets(void)
}; };
static const struct DockWidgetInfo rgDockWidgetInfo[] = { static const struct DockWidgetInfo rgDockWidgetInfo[] = {
{ _uasControlDockWidgetName, "Control", Qt::LeftDockWidgetArea },
{ _uasListDockWidgetName, "Unmanned Systems", Qt::RightDockWidgetArea },
{ _waypointsDockWidgetName, "Mission Plan", Qt::BottomDockWidgetArea }, { _waypointsDockWidgetName, "Mission Plan", Qt::BottomDockWidgetArea },
{ _mavlinkDockWidgetName, "MAVLink Inspector", Qt::RightDockWidgetArea }, { _mavlinkDockWidgetName, "MAVLink Inspector", Qt::RightDockWidgetArea },
{ _customCommandWidgetName, "Custom Command", Qt::RightDockWidgetArea }, { _customCommandWidgetName, "Custom Command", Qt::RightDockWidgetArea },
...@@ -487,11 +483,7 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) ...@@ -487,11 +483,7 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName)
QWidget* widget = NULL; QWidget* widget = NULL;
if (widgetName == _uasControlDockWidgetName) { if (widgetName == _waypointsDockWidgetName) {
widget = new UASControlWidget(this);
} else if (widgetName == _uasListDockWidgetName) {
widget = new UASListWidget(this);
} else if (widgetName == _waypointsDockWidgetName) {
widget = new QGCWaypointListMulti(this); widget = new QGCWaypointListMulti(this);
} else if (widgetName == _mavlinkDockWidgetName) { } else if (widgetName == _mavlinkDockWidgetName) {
widget = new QGCMAVLinkInspector(MAVLinkProtocol::instance(),this); widget = new QGCMAVLinkInspector(MAVLinkProtocol::instance(),this);
...@@ -880,7 +872,7 @@ void MainWindow::_loadCurrentViewState(void) ...@@ -880,7 +872,7 @@ void MainWindow::_loadCurrentViewState(void)
case VIEW_SIMULATION: case VIEW_SIMULATION:
_buildSimView(); _buildSimView();
centerView = _simView; centerView = _simView;
defaultWidgets = "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET,WAYPOINT_LIST_DOCKWIDGET,PARAMETER_INTERFACE_DOCKWIDGET,PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET"; defaultWidgets = "WAYPOINT_LIST_DOCKWIDGET,PARAMETER_INTERFACE_DOCKWIDGET,PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET";
break; break;
default: default:
......
...@@ -41,11 +41,9 @@ This file is part of the QGROUNDCONTROL project ...@@ -41,11 +41,9 @@ This file is part of the QGROUNDCONTROL project
#include "LinkManager.h" #include "LinkManager.h"
#include "LinkInterface.h" #include "LinkInterface.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UASControlWidget.h"
#include "UASInfoWidget.h" #include "UASInfoWidget.h"
#include "WaypointList.h" #include "WaypointList.h"
#include "CameraView.h" #include "CameraView.h"
#include "UASListWidget.h"
#if (defined QGC_MOUSE_ENABLED_WIN) | (defined QGC_MOUSE_ENABLED_LINUX) #if (defined QGC_MOUSE_ENABLED_WIN) | (defined QGC_MOUSE_ENABLED_LINUX)
#include "Mouse6dofInput.h" #include "Mouse6dofInput.h"
#endif // QGC_MOUSE_ENABLED_WIN #endif // QGC_MOUSE_ENABLED_WIN
......
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include <QDoubleSpinBox> #include <QDoubleSpinBox>
#include <QDebug> #include <QDebug>
#include <QGroupBox>
#include <cmath> #include <cmath>
#include <qmath.h> #include <qmath.h>
......
...@@ -279,24 +279,59 @@ Rectangle { ...@@ -279,24 +279,59 @@ Rectangle {
} }
Rectangle { QGCButton {
id: mavIcon width: ScreenTools.defaultFontPixelWidth * 12
width: cellHeight height: cellHeight
height: cellHeight visible: mainToolBar.showMav
visible: mainToolBar.showMav
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
color: colorBlue text: "Vehicle " + activeVehicle.id
border.color: "#00000000"
border.width: 0 menu: vehicleMenu
Image {
source: activeVehicle.systemPixmap Menu {
height: cellHeight * 0.75 id: vehicleMenu
fillMode: Image.PreserveAspectFit }
anchors.verticalCenter: parent.verticalCenter
anchors.horizontalCenter: parent.horizontalCenter Component {
id: vehicleMenuItemComponent
MenuItem {
checkable: true
checked: vehicle.active
onTriggered: multiVehicleManager.activeVehicle = vehicle
property int vehicleId: Number(text.split(" ")[1])
property var vehicle: multiVehicleManager.getVehicleById(vehicleId)
}
}
property var vehicleMenuItems: []
function updateVehicleMenu() {
// Remove old menu items
for (var i=0; i<vehicleMenuItems.length; i++) {
vehicleMenu.removeItem(vehicleMenuItems[i])
}
vehicleMenuItems.length = 0
// Add new items
for (var i=0; i<multiVehicleManager.vehicles.count; i++) {
var vehicle = multiVehicleManager.vehicles.get(i)
var menuItem = vehicleMenuItemComponent.createObject(null, { "text": "Vehicle " + vehicle.id })
vehicleMenuItems.push(menuItem)
vehicleMenu.insertItem(i, menuItem)
}
}
Component.onCompleted: updateVehicleMenu()
Connections {
target: multiVehicleManager.vehicles
onCountChanged: parent.updateVehicleMenu
} }
} }
Rectangle { Rectangle {
id: satelitte id: satelitte
width: getProportionalDimmension(55) width: getProportionalDimmension(55)
...@@ -478,69 +513,92 @@ Rectangle { ...@@ -478,69 +513,92 @@ Rectangle {
} }
} }
Column { QGCButton {
height: cellHeight * 0.85 width: ScreenTools.defaultFontPixelWidth * 11
width: getProportionalDimmension(80) height: cellHeight
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
text: activeVehicle.armed ? "Armed" : "Disarmed"
Rectangle { menu: Menu {
id: armedStatus MenuItem {
width: parent.width enabled: !activeVehicle.armed
height: parent.height / 2 text: "Arm"
anchors.horizontalCenter: parent.horizontalCenter
color: "#00000000"
border.color: "#00000000"
border.width: 0
QGCLabel { onTriggered: activeVehicle.armed = true
id: armedStatusText }
text: (activeVehicle.systemArmed) ? qsTr("ARMED") : qsTr("DISARMED")
font.pixelSize: ScreenTools.smallFontPixelSize MenuItem {
font.weight: Font.DemiBold enabled: activeVehicle.armed
anchors.centerIn: parent text: "Disarm"
color: (activeVehicle.systemArmed) ? colorOrangeText : colorGreenText
onTriggered: activeVehicle.armed = false
} }
} }
}
Rectangle { QGCButton {
id: stateStatus width: ScreenTools.defaultFontPixelWidth * 15
width: parent.width height: cellHeight
height: parent.height / 2 anchors.verticalCenter: parent.verticalCenter
anchors.horizontalCenter: parent.horizontalCenter text: activeVehicle.flightMode
color: "#00000000"
border.color: "#00000000"
border.width: 0
QGCLabel { menu: flightModesMenu
id: stateStatusText
text: activeVehicle.currentState Menu {
font.pixelSize: ScreenTools.smallFontPixelSize id: flightModesMenu
font.weight: Font.DemiBold }
anchors.centerIn: parent
color: (activeVehicle.currentState === "STANDBY") ? colorGreenText : colorRedText Component {
id: flightModeMenuItemComponent
MenuItem {
checkable: true
checked: activeVehicle.flightMode == text
onTriggered: activeVehicle.flightMode = text
}
}
property var flightModesMenuItems: []
function updateFlightModesMenu() {
// Remove old menu items
for (var i=0; i<flightModesMenuItems.length; i++) {
flightModesMenu.removeItem(flightModesMenuItems[i])
}
flightModesMenuItems.length = 0
// Add new items
for (var i=0; i<activeVehicle.flightModes.length; i++) {
var menuItem = flightModeMenuItemComponent.createObject(null, { "text": activeVehicle.flightModes[i] })
flightModesMenuItems.push(menuItem)
flightModesMenu.insertItem(i, menuItem)
} }
} }
Component.onCompleted: updateFlightModesMenu()
Connections {
target: multiVehicleManager
onActiveVehicleChanged: parent.updateFlightModesMenu
}
} }
Rectangle { Rectangle {
id: modeStatus width: ScreenTools.defaultFontPixelWidth * 4
width: getProportionalDimmension(90) height: cellHeight
height: cellHeight anchors.verticalCenter: parent.verticalCenter
color: "#00000000" color: colorBlue
border.color: "#00000000" border.width: 0
border.width: 0 visible: activeVehicle.hilMode
QGCLabel { QGCLabel {
id: modeStatusText anchors.fill: parent
text: activeVehicle.currentMode horizontalAlignment: Text.AlignHCenter
font.pixelSize: ScreenTools.smallFontPixelSize verticalAlignment: Text.AlignVCenter
font.weight: Font.DemiBold text: "HIL"
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
color: colorWhiteText
} }
} }
} // Row } // Row
} // Component - activeVehicleComponent } // Component - activeVehicleComponent
......
...@@ -74,10 +74,7 @@ public slots: ...@@ -74,10 +74,7 @@ public slots:
void setVoltage(UASInterface* uas, double voltage); void setVoltage(UASInterface* uas, double voltage);
void setChargeLevel(UASInterface* uas, double chargeLevel); void setChargeLevel(UASInterface* uas, double chargeLevel);
void setTimeRemaining(UASInterface* uas, double seconds); void setTimeRemaining(UASInterface* uas, double seconds);
// void setBattery(int uasid, BatteryType type, int cells);
// void valueChanged(int uasid, QString key, double value,quint64 time);
// void actuatorChanged(UASInterface* uas, int actId, double value);
void refresh(); void refresh();
protected: protected:
......
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