Commit 46d27b94 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #330 from tstellanova/mvc_decoupling

MVC decoupling of parameters-handling code
parents bb7d4c2d 17afe220
......@@ -285,6 +285,7 @@ class BandMatrixWrapper : public BandMatrixBase<BandMatrixWrapper<_CoefficientsT
m_rows(rows), m_supers(supers), m_subs(subs)
{
//internal::assert(coeffs.cols()==cols() && (supers()+subs()+1)==coeffs.rows());
cols=0; //workaround for compiler warning
}
/** \returns the number of columns */
......
......@@ -468,7 +468,10 @@ HEADERS += src/MG.h \
src/ui/configuration/SerialSettingsDialog.h \
src/ui/configuration/terminalconsole.h \
src/ui/configuration/ApmHighlighter.h \
src/ui/configuration/ApmFirmwareConfig.h
src/ui/configuration/ApmFirmwareConfig.h \
src/uas/UASParameterDataModel.h \
src/uas/UASParameterCommsMgr.h \
src/ui/QGCPendingParamWidget.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
......@@ -683,7 +686,10 @@ SOURCES += src/main.cc \
src/ui/configuration/console.cpp \
src/ui/configuration/SerialSettingsDialog.cc \
src/ui/configuration/ApmHighlighter.cc \
src/ui/configuration/ApmFirmwareConfig.cc
src/ui/configuration/ApmFirmwareConfig.cc \
src/uas/UASParameterDataModel.cc \
src/uas/UASParameterCommsMgr.cc \
src/ui/QGCPendingParamWidget.cc
# 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
......
......@@ -176,7 +176,9 @@ void SerialLink::run()
}
if (isConnected() && (linkErrorCount > 100)) {
qDebug() << "linkErrorCount too high: disconnecting!";
linkErrorCount = 0;
communicationError("SerialLink", tr("Disconnecting on too many link errors"));
disconnect();
}
......@@ -210,7 +212,7 @@ void SerialLink::run()
}
} else {
linkErrorCount++;
qDebug() << "Wait read response timeout" << QTime::currentTime().toString();
//qDebug() << "Wait read response timeout" << QTime::currentTime().toString();
}
if (bytes != m_bytesRead) // i.e things are good and data is being read.
......@@ -370,6 +372,8 @@ bool SerialLink::disconnect()
return true;
}
m_transmitBuffer.clear(); //clear the output buffer to avoid sending garbage at next connect
qDebug() << "already disconnected";
return true;
}
......
#include "QGCUASParamManager.h"
#include <QApplication>>
#include <QDir>
#include "UASInterface.h"
#include "UASParameterCommsMgr.h"
QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) :
QWidget(parent),
mav(uas),
transmissionListMode(false),
transmissionActive(false),
transmissionTimeout(0),
retransmissionTimeout(350),
rewriteTimeout(500),
retransmissionBurstRequestSize(5)
paramDataModel(NULL),
paramCommsMgr(NULL)
{
paramDataModel = uas->getParamDataModel();
paramCommsMgr = uas->getParamCommsMgr();
mav->setParamManager(this);
// Load default values and tooltips
loadParamMetaInfoCSV();
}
bool QGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const
{
return paramDataModel->getOnboardParamValue(component,parameter,value);
}
void QGCUASParamManager::requestParameterUpdate(int component, const QString& parameter)
{
uas->setParamManager(this);
if (mav) {
paramCommsMgr->requestParameterUpdate(component,parameter);
}
}
/**
* The .. signal is emitted
* Send a request to deliver the list of onboard parameters
* to the MAV.
*/
void QGCUASParamManager::requestParameterListUpdate(int component)
void QGCUASParamManager::requestParameterList()
{
if (!mav) {
return;
}
//paramDataModel->forgetAllOnboardParameters(); //TODO really??
setParameterStatusMsg(tr("Requested param list.. waiting"));
paramCommsMgr->requestParameterList();
}
void QGCUASParamManager::setParameterStatusMsg(const QString& msg)
{
Q_UNUSED(component);
qDebug() << "parameterStatusMsg: " << msg;
parameterStatusMsg = msg;
}
void QGCUASParamManager::setParamDescriptions(const QMap<QString,QString>& paramInfo) {
paramDataModel->setParamDescriptions(paramInfo);
}
void QGCUASParamManager::setParameter(int compId, QString paramName, QVariant value)
{
//paramCommsMgr->setParameter(compId,paramName,value);
paramDataModel->updatePendingParamWithValue(compId,paramName,value);
}
void QGCUASParamManager::sendPendingParameters()
{
paramCommsMgr->sendPendingParameters();
}
void QGCUASParamManager::setPendingParam(int compId, QString& paramName, const QVariant& value)
{
paramDataModel->updatePendingParamWithValue(compId,paramName,value);
}
void QGCUASParamManager::loadParamMetaInfoCSV()
{
// Load default values and tooltips
QString autopilot(mav->getAutopilotTypeName());
QDir appDir = QApplication::applicationDirPath();
appDir.cd("files");
QString fileName = QString("%1/%2/parameter_tooltips/tooltips.txt").arg(appDir.canonicalPath()).arg(autopilot.toLower());
QFile paramMetaFile(fileName);
qDebug() << "loadParamMetaInfoCSV for autopilot: " << autopilot << " from file: " << fileName;
if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
qWarning() << "loadParamMetaInfoCSV couldn't open:" << fileName;
return;
}
QTextStream in(&paramMetaFile);
paramDataModel->loadParamMetaInfoFromStream(in);
paramMetaFile.close();
}
/**
* @return The MAV of this mgr. Unless the MAV object has been destroyed, this
* pointer is never zero.
*/
UASInterface* QGCUASParamManager::getUAS()
{
return mav;
}
......@@ -6,7 +6,10 @@
#include <QTimer>
#include <QVariant>
//forward declarations
class UASInterface;
class UASParameterCommsMgr;
class UASParameterDataModel;
class QGCUASParamManager : public QWidget
{
......@@ -14,68 +17,56 @@ class QGCUASParamManager : public QWidget
public:
QGCUASParamManager(UASInterface* uas, QWidget *parent = 0);
QList<QString> getParameterNames(int component) const {
return parameters.value(component)->keys();
}
QList<QVariant> getParameterValues(int component) const {
return parameters.value(component)->values();
}
bool getParameterValue(int component, const QString& parameter, QVariant& value) const {
if (!parameters.contains(component))
{
return false;
}
if (!parameters.value(component)->contains(parameter))
{
return false;
}
value = parameters.value(component)->value(parameter);
return true;
}
virtual bool isParamMinKnown(const QString& param) = 0;
virtual bool isParamMaxKnown(const QString& param) = 0;
virtual bool isParamDefaultKnown(const QString& param) = 0;
virtual double getParamMin(const QString& param) = 0;
virtual double getParamMax(const QString& param) = 0;
virtual double getParamDefault(const QString& param) = 0;
virtual QString getParamInfo(const QString& param) = 0;
virtual void setParamInfo(const QMap<QString,QString>& param) = 0;
/** @brief Request an update for the parameter list */
void requestParameterListUpdate(int component = 0);
/** @brief Request an update for this specific parameter */
virtual void requestParameterUpdate(int component, const QString& parameter) = 0;
/** @brief Get the known, confirmed value of a parameter */
virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const;
/** @brief Provide tooltips / user-visible descriptions for parameters */
virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs);
/** @brief Get the UAS of this widget
* @return The MAV of this mgr. Unless the MAV object has been destroyed, this is never null.
*/
UASInterface* getUAS();
protected:
//TODO decouple this UI message display further?
virtual void setParameterStatusMsg(const QString& msg);
/** @brief Load parameter meta information from appropriate CSV file */
virtual void loadParamMetaInfoCSV();
signals:
void parameterChanged(int component, QString parameter, QVariant value);
void parameterChanged(int component, int parameterIndex, QVariant value);
void parameterListUpToDate(int component);
public slots:
/** @brief Write one parameter to the MAV */
virtual void setParameter(int component, QString parameterName, QVariant value) = 0;
/** @brief Send one parameter to the MAV: changes value in transient memory of MAV */
virtual void setParameter(int component, QString parameterName, QVariant value);
/** @brief Send all pending parameters to the MAV, for storage in transient (RAM) memory */
virtual void sendPendingParameters();
/** @brief Request list of parameters from MAV */
virtual void requestParameterList() = 0;
virtual void requestParameterList();
virtual void setPendingParam(int componentId, QString& key, const QVariant& value);
/** @brief Request a single parameter by name from the MAV */
virtual void requestParameterUpdate(int component, const QString& parameter);
virtual void handleParameterUpdate(int component, const QString& parameterName, QVariant value) = 0;
virtual void handleParameterListUpToDate() = 0;
protected:
UASInterface* mav; ///< The MAV this widget is controlling
QMap<int, QMap<QString, QVariant>* > changedValues; ///< Changed values
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
QVector<bool> received; ///< Successfully received parameters
QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets
QMap<int, QMap<QString, QVariant>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list?
quint64 transmissionTimeout; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission
int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds
int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
// Parameter data model
UASInterface* mav; ///< The MAV this manager is controlling
UASParameterDataModel* paramDataModel;///< Shared data model of parameters
UASParameterCommsMgr* paramCommsMgr; ///< Shared comms mgr for parameters
// Status
QString parameterStatusMsg;
};
......
......@@ -26,6 +26,7 @@
#include "QGCMAVLink.h"
#include "LinkManager.h"
#include "SerialLink.h"
#include "UASParameterCommsMgr.h"
#include <Eigen/Geometry>
#ifdef QGC_PROTOBUF_ENABLED
......@@ -131,6 +132,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
paramsOnceRequested(false),
paramManager(NULL),
paramDataModel(NULL),
paramCommsMgr(NULL),
simulation(0),
......@@ -151,6 +154,11 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
componentMulti[i] = false;
}
paramDataModel = new UASParameterDataModel(this);
paramDataModel->setUASID(this->getUASID());
paramCommsMgr = new UASParameterCommsMgr(this,this);
// Store a list of available actions for this UAS.
// Basically everything exposted as a SLOT with no return value or arguments.
......@@ -226,6 +234,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
*/
UAS::~UAS()
{
delete paramCommsMgr;
delete paramDataModel;
writeSettings();
delete links;
delete statusTimeout;
......@@ -1991,7 +2001,7 @@ void UAS::sendMessage(mavlink_message_t message)
if (LinkManager::instance()->getLinks().contains(link))
{
sendMessage(link, message);
qDebug() << "SENT MESSAGE!";
qDebug() << "SENT MESSAGE id" << message.msgid << "component" << message.compid;
}
else
{
......@@ -2021,8 +2031,10 @@ void UAS::forwardMessage(mavlink_message_t message)
{
if(serial != links->at(i))
{
qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
sendMessage(serial, message);
if (link->isConnected()) {
qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
sendMessage(serial, message);
}
}
}
}
......@@ -2247,7 +2259,9 @@ void UAS::requestParameters()
mavlink_message_t msg;
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
sendMessage(msg);
qDebug() << __FILE__ << ":" << __LINE__ << "LOADING PARAM LIST";
QDateTime time = QDateTime::currentDateTime();
qDebug() << __FILE__ << ":" << __LINE__ << time.toString() << "LOADING PARAM LIST";
}
void UAS::writeParametersToStorage()
......@@ -2533,7 +2547,7 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
switch (value.type())
switch ((int)value.type())
{
case QVariant::Char:
union_value.param_float = (unsigned char)value.toChar().toAscii();
......@@ -2558,7 +2572,7 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
}
else
{
switch (value.type())
switch ((int)value.type())
{
case QVariant::Char:
union_value.param_int8 = (unsigned char)value.toChar().toAscii();
......
......@@ -41,6 +41,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCJSBSimLink.h"
#include "QGCXPlaneLink.h"
/**
* @brief A generic MAVLINK-connected MAV/UAV
*
......@@ -492,6 +493,8 @@ protected: //COMMENTS FOR TEST UNIT
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
QGCUASParamManager* paramManager; ///< Parameter manager class
UASParameterDataModel* paramDataModel; ///< The parameter data model for this UAS
UASParameterCommsMgr* paramCommsMgr;
/// SIMULATION
QGCHilLink* simulation; ///< Hardware in the loop simulation link
......@@ -519,10 +522,24 @@ public:
QGCUASParamManager* getParamManager() const {
return paramManager;
}
/** @brief Get reference to the parameter data model (same one shared with the parameter manager) **/
UASParameterDataModel* getParamDataModel() {
return paramDataModel;
}
UASParameterCommsMgr* getParamCommsMgr() {
return paramCommsMgr;
}
/** @brief Get the HIL simulation */
QGCHilLink* getHILSimulation() const {
return simulation;
}
// TODO Will be removed
/** @brief Set reference to the param manager **/
void setParamManager(QGCUASParamManager* manager) {
......@@ -949,6 +966,7 @@ protected:
quint64 lastSendTimeSensors;
QList<QAction*> actions; ///< A list of actions that this UAS can perform.
protected slots:
/** @brief Write settings to disk */
void writeSettings();
......
......@@ -40,6 +40,7 @@ This file is part of the QGROUNDCONTROL project
#include "LinkInterface.h"
#include "ProtocolInterface.h"
#include "UASParameterDataModel.h"
#include "UASWaypointManager.h"
#include "QGCUASParamManager.h"
#include "RadioCalibration/RadioCalibrationData.h"
......@@ -152,8 +153,16 @@ public:
/** @brief Get reference to the waypoint manager **/
virtual UASWaypointManager* getWaypointManager(void) = 0;
/** @brief Access the parameter data model for this UAS (sans widget). This is the same parameter data model used by the parameter manager. **/
virtual UASParameterDataModel* getParamDataModel() = 0;
virtual UASParameterCommsMgr* getParamCommsMgr() = 0;
/** @brief Get reference to the param manager **/
virtual QGCUASParamManager* getParamManager() const = 0;
// TODO Will be removed
/** @brief Set reference to the param manager **/
virtual void setParamManager(QGCUASParamManager* manager) = 0;
......
......@@ -280,6 +280,7 @@ void UASManager::addUAS(UASInterface* uas)
// Only execute if there is no UAS at this index
if (!systems.contains(uas))
{
qDebug() << "Add new UAS: " << uas->getUASID();
systems.append(uas);
// Set home position on UAV if set in UI
// - this is done on a per-UAV basis
......
This diff is collapsed.
#ifndef UASPARAMETERCOMMSMGR_H
#define UASPARAMETERCOMMSMGR_H
#include <QObject>
#include <QMap>
#include <QTimer>
#include <QVariant>
#include <QVector>
class UASInterface;
class UASParameterDataModel;
class UASParameterCommsMgr : public QObject
{
Q_OBJECT
public:
explicit UASParameterCommsMgr(QObject *parent = 0, UASInterface* uas = NULL);
~UASParameterCommsMgr();
typedef enum ParamCommsStatusLevel {
ParamCommsStatusLevel_OK = 0,
ParamCommsStatusLevel_Warning = 2,
ParamCommsStatusLevel_Error = 4,
ParamCommsStatusLevel_Count
} ParamCommsStatusLevel_t;
protected:
/** @brief Activate / deactivate parameter retransmission */
virtual void setRetransmissionGuardEnabled(bool enabled);
virtual void setParameterStatusMsg(const QString& msg, ParamCommsStatusLevel_t level=ParamCommsStatusLevel_OK);
/** @brief Load settings that control eg retransmission timeouts */
void loadParamCommsSettings();
/** @brief clear transmissionMissingPackets and transmissionMissingWriteAckPackets */
void clearRetransmissionLists(int& missingReadCount, int& missingWriteCount );
void resendReadWriteRequests();
void resetAfterListReceive();
void emitPendingParameterCommit(int compId, const QString& key, QVariant& value);
signals:
void commitPendingParameter(int component, QString parameter, QVariant value);
void parameterChanged(int component, int parameterIndex, QVariant value);
void parameterValueConfirmed(int uas, int component,int paramCount, int paramId, QString parameter, QVariant value);
/** @brief We have received a complete list of all parameters onboard the MAV */
void parameterListUpToDate();
void parameterUpdateRequested(int component, const QString& parameter);
void parameterUpdateRequestedById(int componentId, int paramId);
/** @brief We updated the parameter status message */
void parameterStatusMsgUpdated(QString msg, int level);
public slots:
/** @brief Iterate through all components, through all pending parameters and send them to UAS */
virtual void sendPendingParameters();
/** @brief Write the current onboard parameters from transient RAM into persistent storage, e.g. EEPROM or harddisk */
virtual void writeParamsToPersistentStorage();
/** @brief Write one parameter to the MAV */
virtual void setParameter(int component, QString parameterName, QVariant value);
/** @brief Request list of parameters from MAV */
virtual void requestParameterList();
/** @brief Check for missing parameters */
virtual void retransmissionGuardTick();
/** @brief Request a single parameter update by name */
virtual void requestParameterUpdate(int component, const QString& parameter);
/** @brief Request an update of RC parameters */
virtual void requestRcCalibrationParamsUpdate();
virtual void receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value);
protected:
UASInterface* mav; ///< The MAV we're talking to
UASParameterDataModel* paramDataModel;
// Communications management
QVector<bool> receivedParamsList; ///< Successfully received parameters
QMap<int, QList<int>* > missingReadPackets; ///< Missing packets
QMap<int, QMap<QString, QVariant>* > missingWriteAckPackets; ///< Missing write ACK packets
bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list?
quint64 transmissionTimeout; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission
quint64 lastTimerReset; ///< Last time the guard timer was reset, to prevent premature firing
int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds
int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
quint64 listRecvTimeout; ///< How long to wait for first parameter list response before re-requesting
// Status
QString parameterStatusMsg;
};
#endif // UASPARAMETERCOMMSMGR_H
This diff is collapsed.
#ifndef UASPARAMETERDATAMODEL_H
#define UASPARAMETERDATAMODEL_H
#include <QMap>
#include <QObject>
#include <QVariant>
class QTextStream;
class UASParameterDataModel : public QObject
{
Q_OBJECT
public:
explicit UASParameterDataModel(QObject *parent = 0);
//Parameter meta info
bool isParamMinKnown(const QString& param) { return paramMin.contains(param); }
virtual bool isValueLessThanParamMin(const QString& param, double dblVal);
bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); }
virtual bool isValueGreaterThanParamMax(const QString& param, double dblVal);
bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); }
double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); }
double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); }
double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); }
virtual QString getParamDescription(const QString& param) { return paramDescriptions.value(param, ""); }
virtual void setParamDescriptions(const QMap<QString,QString>& paramInfo);
//TODO make this method protected?
/** @brief Ensure that the data model is aware of this component
* @param compId Id of the component
*/
virtual void addComponent(int compId);
/** @brief Save the onboard parameter with a the type specified in the QVariant as fixed */
virtual void setOnboardParamWithType(int componentId, QString& key, QVariant& value);
/** @brief clears every parameter for every loaded component */
virtual void forgetAllOnboardParams();
/** @brief add this parameter to pending list iff it has changed from onboard value
* @return true if the parameter is now pending
*/
virtual bool updatePendingParamWithValue(int componentId, QString& key, const QVariant &value);
virtual void handleParamUpdate(int componentId, QString& key, QVariant& value);
virtual bool getOnboardParamValue(int componentId, const QString& key, QVariant& value) const;
virtual bool isParamChangePending(int componentId,const QString& key);
QMap<QString , QVariant>* getPendingParamsForComponent(int componentId) {
return pendingParameters.value(componentId);
}
QMap<QString , QVariant>* getOnboardParamsForComponent(int componentId) {
return onboardParameters.value(componentId);
}
QMap<int, QMap<QString, QVariant>* >* getAllPendingParams() {
return &pendingParameters;
}
QMap<int, QMap<QString, QVariant>* >* getAllOnboardParams() {
return &onboardParameters;
}
/** @brief return a count of all pending parameters */
int countPendingParams();
virtual void writeOnboardParamsToStream(QTextStream &stream, const QString& uasName);
virtual void readUpdateParamsFromStream(QTextStream &stream);
virtual void loadParamMetaInfoFromStream(QTextStream& stream);
void setUASID(int anId) { this->uasId = anId; }
protected:
/** @brief set the confirmed value of a parameter in the onboard params list */
virtual void setOnboardParam(int componentId, QString& key, const QVariant& value);
/** @brief Write a new pending parameter value that may be eventually sent to the UAS */
virtual void setPendingParam(int componentId, QString& key, const QVariant& value);
/** @brief remove a parameter from the pending list */
virtual void removePendingParam(int compId, QString& key);
signals:
/** @brief We've received an update of a parameter's value */
void parameterUpdated(int compId, QString paramName, QVariant value);
/** @brief Notifies listeners that a param was added to or removed from the pending list */
void pendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending);
void allPendingParamsCommitted(); ///< All pending params have been committed to the MAV
public slots:
protected:
int uasId; ///< The UAS / MAV to which this data model pertains
QMap<int, QMap<QString, QVariant>* > pendingParameters; ///< Changed values that have not yet been transmitted to the UAS, by component ID
QMap<int, QMap<QString, QVariant>* > onboardParameters; ///< All parameters confirmed to be stored onboard the UAS, by component ID
// Tooltip data structures
QMap<QString, QString> paramDescriptions; ///< Tooltip values
// Min / Default / Max data structures
QMap<QString, double> paramMin; ///< Minimum param values
QMap<QString, double> paramDefault; ///< Default param values
QMap<QString, double> paramMax; ///< Minimum param values
};
#endif // UASPARAMETERDATAMODEL_H
......@@ -975,7 +975,9 @@ void UASWaypointManager::sendWaypointRequestList()
wprl.target_system = uasid;
wprl.target_component = MAV_COMP_ID_MISSIONPLANNER;
emit updateStatusString(QString("Requesting waypoint list..."));
QString statusMsg(tr("Requesting waypoint list..."));
qDebug() << __FILE__ << __LINE__ << statusMsg;
emit updateStatusString(statusMsg);
mavlink_msg_mission_request_list_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wprl);
uas->sendMessage(message);
......
......@@ -950,35 +950,60 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
if (uas)
{
connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
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(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(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
connect(uas, SIGNAL(gyroStatusChanged(bool,bool,bool)), this, SLOT(updateGyroStatus(bool,bool,bool)));
connect(uas, SIGNAL(accelStatusChanged(bool,bool,bool)), this, SLOT(updateAccelStatus(bool,bool,bool)));
connect(uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)), this, SLOT(updateMagSensorStatus(bool,bool,bool)));
connect(uas, SIGNAL(baroStatusChanged(bool,bool,bool)), this, SLOT(updateBaroStatus(bool,bool,bool)));
connect(uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)), this, SLOT(updateAirspeedStatus(bool,bool,bool)));
connect(uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)), this, SLOT(updateOpticalFlowStatus(bool,bool,bool)));
connect(uas, SIGNAL(laserStatusChanged(bool,bool,bool)), this, SLOT(updateLaserStatus(bool,bool,bool)));
connect(uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)), this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool)));
connect(uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)), this, SLOT(updateActuatorStatus(bool,bool,bool)));
connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)),
this, SLOT(updateSatellite(int,int,float,float,float,bool)));
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(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(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)));
connect(uas, SIGNAL(positionXYControlEnabled(bool)),
this, SLOT(updatePositionXYControllerEnabled(bool)));
connect(uas, SIGNAL(positionZControlEnabled(bool)),
this, SLOT(updatePositionZControllerEnabled(bool)));
connect(uas, SIGNAL(positionYawControlEnabled(bool)),
this, SLOT(updatePositionYawControllerEnabled(bool)));
connect(uas, SIGNAL(localizationChanged(UASInterface*,int)),
this, SLOT(updateLocalization(UASInterface*,int)));
connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)),
this, SLOT(updateVisionLocalization(UASInterface*,int)));
connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)),
this, SLOT(updateGpsLocalization(UASInterface*,int)));
connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)),
this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)),
this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
connect(uas, SIGNAL(gyroStatusChanged(bool,bool,bool)),
this, SLOT(updateGyroStatus(bool,bool,bool)));
connect(uas, SIGNAL(accelStatusChanged(bool,bool,bool)),
this, SLOT(updateAccelStatus(bool,bool,bool)));
connect(uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)),
this, SLOT(updateMagSensorStatus(bool,bool,bool)));
connect(uas, SIGNAL(baroStatusChanged(bool,bool,bool)),
this, SLOT(updateBaroStatus(bool,bool,bool)));
connect(uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)),
this, SLOT(updateAirspeedStatus(bool,bool,bool)));
connect(uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)),
this, SLOT(updateOpticalFlowStatus(bool,bool,bool)));
connect(uas, SIGNAL(laserStatusChanged(bool,bool,bool)),
this, SLOT(updateLaserStatus(bool,bool,bool)));
connect(uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)),
this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool)));
connect(uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)),
this, SLOT(updateActuatorStatus(bool,bool,bool)));
statusClearTimer.start(3000);
}
else
......
......@@ -72,6 +72,7 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
ParameterInterface::~ParameterInterface()
{
delete paramWidgets;
delete m_ui;
}
......@@ -89,8 +90,20 @@ void ParameterInterface::selectUAS(int index)
*/
void ParameterInterface::addUAS(UASInterface* uas)
{
int uasId = uas->getUASID();
qDebug() << "ParameterInterface::addUAS : " << uasId ;
if (paramWidgets->contains(uasId) ) {
return;
}
QGCParamWidget* param = new QGCParamWidget(uas, this);
paramWidgets->insert(uas->getUASID(), param);
param->init();
QString ptrStr;
ptrStr.sprintf("QGCParamWidget %8p (parent %8p)", param,this);
qDebug() << "Created " << ptrStr << " for UAS id: " << uasId << " count: " << paramWidgets->count();
paramWidgets->insert(uasId, param);
m_ui->stackedWidget->addWidget(param);
QGCSensorSettingsWidget* sensor = NULL;
......
......@@ -267,15 +267,24 @@ void PrimaryFlightDisplay::forgetUAS(UASInterface* uas)
{
if (this->uas != NULL && this->uas == uas) {
// 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(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
disconnect(this->uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64)));
disconnect(this->uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSSpeed(UASInterface*,double,quint64)));
disconnect(this->uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this, SLOT(updateClimbRate(UASInterface*, AltitudeMeasurementSource, double, quint64)));
disconnect(this->uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64)));
disconnect(this->uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSAltitude(UASInterface*, double, quint64)));
disconnect(this->uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)), this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double)));
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(waypointSelected(int,int)),
// this, SLOT(selectWaypoint(int, int)));
disconnect(this->uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)),
this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64)));
disconnect(this->uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)),
this, SLOT(updateGPSSpeed(UASInterface*,double,quint64)));
disconnect(this->uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)),
this,SLOT(updateClimbRate(UASInterface*, double, quint64)));
disconnect(this->uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)),
this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64)));
disconnect(this->uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)),
this, SLOT(updateGPSAltitude(UASInterface*, double, quint64)));
disconnect(this->uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)),
this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double)));
//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)));
......@@ -314,10 +323,12 @@ void PrimaryFlightDisplay::setActiveUAS(UASInterface* uas)
//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(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
//connect(uas, SIGNAL(waypointSelected(int,int)), this,
// SLOT(selectWaypoint(int, int)));
connect(uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64)));
connect(uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSSpeed(UASInterface*,double,quint64)));
connect(uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this, SLOT(updateClimbRate(UASInterface*, AltitudeMeasurementSource, double, quint64)));
connect(uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this,
SLOT(updateClimbRate(UASInterface*, double, quint64)));
connect(uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64)));
connect(uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSAltitude(UASInterface*, double, quint64)));
connect(uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)), this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double)));
......
......@@ -8,7 +8,7 @@
QGCConfigView::QGCConfigView(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCConfigView),
currUAS(NULL)
mav(NULL)
{
ui->setupUi(this);
......@@ -26,7 +26,7 @@ QGCConfigView::~QGCConfigView()
void QGCConfigView::activeUASChanged(UASInterface* uas)
{
if (currUAS == uas)
if (mav == uas)
return;
//remove all child widgets since they could contain stale data
......@@ -41,11 +41,13 @@ void QGCConfigView::activeUASChanged(UASInterface* uas)
}
}
if (NULL != uas) {
mav = uas;
if (NULL != mav) {
ui->gridLayout->removeWidget(ui->waitingLabel);
ui->waitingLabel->setVisible(false);
switch (uas->getAutopilotType()) {
int autopilotType = mav->getAutopilotType();
switch (autopilotType) {
case MAV_AUTOPILOT_PX4:
ui->gridLayout->addWidget(new QGCPX4VehicleConfig());
break;
......
......@@ -21,7 +21,7 @@ public slots:
private:
Ui::QGCConfigView *ui;
UASInterface* currUAS;
UASInterface* mav;
};
......
......@@ -13,9 +13,12 @@
#include <QMessageBox>
#include "QGCPX4VehicleConfig.h"
#include "UASManager.h"
#include "QGC.h"
#include "QGCPendingParamWidget.h"
#include "QGCToolWidget.h"
#include "UASManager.h"
#include "UASParameterCommsMgr.h"
#include "ui_QGCPX4VehicleConfig.h"
......@@ -80,7 +83,9 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
//connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));
//TODO connect buttons here to save/clear actions?
ui->pendingCommitsWidget->init();
ui->pendingCommitsWidget->update();
//TODO the following methods are not yet implemented
......@@ -299,7 +304,6 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary)
}
// Generate widgets for the Advanced tab.
left = true;
foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot))
{
if (file.toLower().endsWith(".qgw")) {
......@@ -793,9 +797,12 @@ void QGCPX4VehicleConfig::loadConfig()
xml.readNext();
}
mav->getParamManager()->setParamInfo(paramTooltips);
if (!paramTooltips.isEmpty()) {
mav->getParamManager()->setParamDescriptions(paramTooltips);
}
doneLoadingConfig = true;
mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
//Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
mav->getParamCommsMgr()->requestParameterList();
}
void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
......@@ -824,31 +831,28 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
// Disconnect old system
disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
SLOT(remoteControlChannelRawChanged(int,float)));
//TODO use paramCommsMgr instead
disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
SLOT(parameterChanged(int,int,QString,QVariant)));
disconnect(ui->refreshButton,SIGNAL(clicked()),mav,SLOT(requestParameters()));
disconnect(ui->refreshButton,SIGNAL(clicked()),
paramCommsMgr,SLOT(requestParameterList()));
// Delete all children from all fixed tabs.
foreach(QWidget* child, ui->generalLeftContents->findChildren<QWidget*>())
{
foreach(QWidget* child, ui->generalLeftContents->findChildren<QWidget*>()) {
child->deleteLater();
}
foreach(QWidget* child, ui->generalRightContents->findChildren<QWidget*>())
{
foreach(QWidget* child, ui->generalRightContents->findChildren<QWidget*>()) {
child->deleteLater();
}
foreach(QWidget* child, ui->advanceColumnContents->findChildren<QWidget*>())
{
foreach(QWidget* child, ui->advanceColumnContents->findChildren<QWidget*>()) {
child->deleteLater();
}
foreach(QWidget* child, ui->sensorContents->findChildren<QWidget*>())
{
foreach(QWidget* child, ui->sensorContents->findChildren<QWidget*>()) {
child->deleteLater();
}
// And then delete any custom tabs
foreach(QWidget* child, additionalTabs)
{
foreach(QWidget* child, additionalTabs) {
child->deleteLater();
}
additionalTabs.clear();
......@@ -864,6 +868,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
// Connect new system
mav = active;
paramCommsMgr = mav->getParamCommsMgr();
// Reset current state
resetCalibrationRC();
......@@ -873,26 +878,24 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
chanCount = 0;
// Connect new system
connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
connect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
SLOT(remoteControlChannelRawChanged(int,float)));
connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
SLOT(parameterChanged(int,int,QString,QVariant)));
connect(ui->refreshButton, SIGNAL(clicked()), active, SLOT(requestParameters()));
connect(ui->refreshButton, SIGNAL(clicked()),
paramCommsMgr,SLOT(requestParameterList()));
if (systemTypeToParamMap.contains(mav->getSystemTypeName()))
{
if (systemTypeToParamMap.contains(mav->getSystemTypeName())) {
paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
}
else
{
else {
//Indication that we have no meta data for this system type.
qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
}
if (!paramTooltips.isEmpty())
{
mav->getParamManager()->setParamInfo(paramTooltips);
if (!paramTooltips.isEmpty()) {
mav->getParamManager()->setParamDescriptions(paramTooltips);
}
qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
......@@ -910,8 +913,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
ui->writeButton->setEnabled(true);
ui->loadFileButton->setEnabled(true);
ui->saveFileButton->setEnabled(true);
if (mav->getAutopilotTypeName() == "ARDUPILOTMEGA")
{
if (mav->getAutopilotTypeName() == "ARDUPILOTMEGA") {
ui->readButton->hide();
ui->writeButton->hide();
}
......@@ -941,6 +943,7 @@ void QGCPX4VehicleConfig::writeCalibrationRC()
// Do not write the RC type, as these values depend on this
// active onboard parameter
//TODO consolidate RC param sending in the UAS comms mgr
for (unsigned int i = 0; i < chanCount; ++i)
{
//qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
......@@ -975,26 +978,8 @@ void QGCPX4VehicleConfig::writeCalibrationRC()
void QGCPX4VehicleConfig::requestCalibrationRC()
{
if (!mav) return;
QString minTpl("RC%1_MIN");
QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM");
QString revTpl("RC%1_REV");
// Do not request the RC type, as these values depend on this
// active onboard parameter
for (unsigned int i = 0; i < chanMax; ++i)
{
mav->requestParameter(0, minTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
mav->requestParameter(0, trimTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
mav->requestParameter(0, maxTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
mav->requestParameter(0, revTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
if (paramCommsMgr) {
paramCommsMgr->requestRcCalibrationParamsUpdate();
}
}
......@@ -1249,8 +1234,6 @@ void QGCPX4VehicleConfig::handleRcParameterChange(QString parameterName, QVarian
void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
Q_UNUSED(uas);
Q_UNUSED(component);
if (!doneLoadingConfig) {
//We do not want to attempt to generate any UI elements until loading of the config file is complete.
//We should re-request params later if needed, that is not implemented yet.
......
......@@ -10,6 +10,8 @@
#include "QGCToolWidget.h"
#include "UASInterface.h"
class UASParameterCommsMgr;
namespace Ui {
class QGCPX4VehicleConfig;
}
......@@ -159,6 +161,7 @@ protected slots:
protected:
bool doneLoadingConfig;
UASInterface* mav; ///< The current MAV
UASParameterCommsMgr* paramCommsMgr; ///< param comms mgr for the mav
static const unsigned int chanMax = 8; ///< Maximum number of channels
unsigned int chanCount; ///< Actual channels
int rcType; ///< Type of the remote control
......@@ -184,6 +187,7 @@ protected:
QTimer updateTimer; ///< Controls update intervals
enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention
QList<QGCToolWidget*> toolWidgets; ///< Configurable widgets
QMap<QString,QGCToolWidget*> toolWidgetsByName; ///<
bool calibrationEnabled; ///< calibration mode on / off
QMap<QString,QGCToolWidget*> paramToWidgetMap; ///< Holds the current active MAV's parameter widgets.
......
......@@ -138,7 +138,7 @@ Config</string>
<item>
<widget class="QStackedWidget" name="stackedWidget">
<property name="currentIndex">
<number>0</number>
<number>3</number>
</property>
<widget class="QWidget" name="rcTab">
<layout class="QVBoxLayout" name="verticalLayout_17">
......@@ -1035,8 +1035,8 @@ p, li { white-space: pre-wrap; }
<rect>
<x>0</x>
<y>0</y>
<width>16</width>
<height>16</height>
<width>597</width>
<height>569</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
......@@ -1168,7 +1168,17 @@ p, li { white-space: pre-wrap; }
<number>0</number>
</property>
<item>
<widget class="QTreeView" name="pendingCommitsTreeView"/>
<widget class="QGCPendingParamWidget" name="pendingCommitsWidget" native="true">
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
</size>
</property>
<property name="autoFillBackground">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="setButton">
......@@ -1259,6 +1269,12 @@ p, li { white-space: pre-wrap; }
<header>ui/designer/QGCRadioChannelDisplay.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>QGCPendingParamWidget</class>
<extends>QWidget</extends>
<header>/ui/QGCPendingParamWidget.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
......
This diff is collapsed.
......@@ -48,40 +48,39 @@ class QGCParamWidget : public QGCUASParamManager
Q_OBJECT
public:
QGCParamWidget(UASInterface* uas, QWidget *parent = 0);
/** @brief Get the UAS of this widget */
UASInterface* getUAS();
bool isParamMinKnown(const QString& param) { return paramMin.contains(param); }
bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); }
bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); }
double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); }
double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); }
double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); }
QString getParamInfo(const QString& param) { return paramToolTips.value(param, ""); }
void setParamInfo(const QMap<QString,QString>& param) { paramToolTips = param; }
virtual void init(); ///< Two-stage construction: initialize the object
protected:
virtual void setParameterStatusMsg(const QString& msg);
virtual void layoutWidget();///< Layout the appearance of this widget
virtual void connectSignalsAndSlots();///< Connect signals/slots as needed
virtual QTreeWidgetItem* getParentWidgetItemForParam(int compId, const QString& paramName);
virtual QTreeWidgetItem* findChildWidgetItemForParam(QTreeWidgetItem* parentItem, const QString& paramName);
signals:
/** @brief A parameter was changed in the widget, NOT onboard */
//void parameterChanged(int component, QString parametername, float value); // defined in QGCUASParamManager already
/** @brief Request a single parameter */
void requestParameter(int component, int parameter);
/** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
public slots:
/** @brief Add a component to the list */
void addComponent(int uas, int component, QString componentName);
/** @brief Add a parameter to the list with retransmission / safety checks */
void addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value);
/** @brief Add a parameter to the list */
void addParameter(int uas, int component, QString parameterName, QVariant value);
/** @brief Add a component to the list
* @param compId Component id of the component
* @param compName Human friendly name of the component
*/
void addComponentItem(int compId, QString compName);
virtual void handleParameterUpdate(int component,const QString& parameterName, QVariant value);
virtual void handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending);
virtual void handleParameterListUpToDate();
virtual void handleParamStatusMsgUpdate(QString msg, int level);
/** @brief Ensure that view of parameter matches data in the model */
QTreeWidgetItem* updateParameterDisplay(int component, QString parameterName, QVariant value);
/** @brief Request list of parameters from MAV */
void requestParameterList();
/** @brief Request one single parameter */
void requestParameterUpdate(int component, const QString& parameter);
/** @brief Set one parameter, changes value in RAM of MAV */
void setParameter(int component, QString parameterName, QVariant value);
/** @brief Set all parameters, changes the value in RAM of MAV */
void setParameters();
void requestAllParamsUpdate();
/** @brief Write the current parameters to permanent storage (EEPROM/HDD) */
void writeParameters();
/** @brief Read the parameters from permanent storage to RAM */
......@@ -92,32 +91,19 @@ public slots:
void parameterItemChanged(QTreeWidgetItem* prev, int column);
/** @brief Store parameters to a file */
void saveParameters();
void saveParametersToFile();
/** @brief Load parameters from a file */
void loadParameters();
void loadParametersFromFile();
/** @brief Check for missing parameters */
void retransmissionGuardTick();
protected:
QTreeWidget* tree; ///< The parameter tree
QLabel* statusLabel; ///< Parameter transmission label
QMap<int, QTreeWidgetItem*>* components; ///< The list of components
QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups
// Tooltip data structures
QMap<QString, QString> paramToolTips; ///< Tooltip values
// Min / Default / Max data structures
QMap<QString, double> paramMin; ///< Minimum param values
QMap<QString, double> paramDefault; ///< Default param values
QMap<QString, double> paramMax; ///< Minimum param values
/** @brief Activate / deactivate parameter retransmission */
void setRetransmissionGuardEnabled(bool enabled);
/** @brief Load settings */
void loadSettings();
/** @brief Load meta information from CSV */
void loadParameterInfoCSV(const QString& autopilot, const QString& airframe);
QLabel* statusLabel; ///< User-facing parameter status label
QMap<int, QTreeWidgetItem*>* componentItems; ///< The tree of component items, stored by component ID
QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups to organize component items
QString updatingParamNameLock; ///< Name of param currently being updated-- used for reducing echo on param change
};
#endif // QGCPARAMWIDGET_H
#include "QGCPendingParamWidget.h"
#include "UASManager.h"
#include "UASParameterCommsMgr.h"
QGCPendingParamWidget::QGCPendingParamWidget(QObject *parent) :
QGCParamWidget(UASManager::instance()->getActiveUAS(),(QWidget*)parent)
{
}
void QGCPendingParamWidget::init()
{
//we override a lot of the super's init methods
layoutWidget();
connectSignalsAndSlots();
//don't request update params here...assume that everything we need is in the data model
}
void QGCPendingParamWidget::connectSignalsAndSlots()
{
// Listing for pending list update
connect(paramDataModel, SIGNAL(pendingParamUpdate(int , const QString&, QVariant , bool )),
this, SLOT(handlePendingParamUpdate(int , const QString& , QVariant, bool )));
// Listen to communications status messages so we can display them
connect(paramCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)),
this, SLOT(handleParamStatusMsgUpdate(QString , int )));
}
void QGCPendingParamWidget::handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending)
{
// qDebug() << "handlePendingParamUpdate:" << paramName << "with updatingParamNameLock:" << updatingParamNameLock;
if (updatingParamNameLock == paramName) {
//qDebug() << "ignoring bounce from " << paramName;
return;
}
else {
updatingParamNameLock = paramName;
}
QTreeWidgetItem* paramItem = updateParameterDisplay(compId,paramName,value);
if (isPending) {
QTreeWidgetItem* paramItem = updateParameterDisplay(compId,paramName,value);
paramItem->setFlags(paramItem->flags() & ~Qt::ItemIsEditable); //disallow editing
paramItem->setBackground(0, QBrush(QColor(QGC::colorOrange)));
paramItem->setBackground(1, QBrush(QColor(QGC::colorOrange)));
tree->expandAll();
}
else {
//we don't display non-pending items
paramItem->parent()->removeChild(paramItem);
}
updatingParamNameLock.clear();
}
#ifndef QGCPENDINGPARAMWIDGET_H
#define QGCPENDINGPARAMWIDGET_H
#include "QGCParamWidget.h"
class QGCPendingParamWidget : public QGCParamWidget
{
Q_OBJECT
public:
explicit QGCPendingParamWidget(QObject* parent);
virtual void init(); ///< Two-stage construction: initialize the object
protected:
virtual void connectSignalsAndSlots();
signals:
public slots:
virtual void handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending);
};
#endif // QGCPENDINGPARAMWIDGET_H
......@@ -13,9 +13,11 @@
#include <QMessageBox>
#include "QGCVehicleConfig.h"
#include "UASManager.h"
#include "QGC.h"
#include "QGCToolWidget.h"
#include "UASManager.h"
#include "UASParameterCommsMgr.h"
#include "ui_QGCVehicleConfig.h"
QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
......@@ -786,9 +788,10 @@ void QGCVehicleConfig::loadConfig()
xml.readNext();
}
mav->getParamManager()->setParamInfo(paramTooltips);
mav->getParamManager()->setParamDescriptions(paramTooltips);
doneLoadingConfig = true;
mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
//Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
mav->getParamCommsMgr()->requestParameterList();
}
void QGCVehicleConfig::setActiveUAS(UASInterface* active)
......@@ -888,7 +891,7 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
if (!paramTooltips.isEmpty())
{
mav->getParamManager()->setParamInfo(paramTooltips);
mav->getParamManager()->setParamDescriptions(paramTooltips);
}
qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
......@@ -937,6 +940,7 @@ void QGCVehicleConfig::writeCalibrationRC()
// Do not write the RC type, as these values depend on this
// active onboard parameter
//TODO consolidate RC param sending in the UAS comms mgr
for (unsigned int i = 0; i < chanCount; ++i)
{
//qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
......@@ -971,26 +975,8 @@ void QGCVehicleConfig::writeCalibrationRC()
void QGCVehicleConfig::requestCalibrationRC()
{
if (!mav) return;
QString minTpl("RC%1_MIN");
QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM");
QString revTpl("RC%1_REV");
// Do not request the RC type, as these values depend on this
// active onboard parameter
for (unsigned int i = 0; i < chanMax; ++i)
{
mav->requestParameter(0, minTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
mav->requestParameter(0, trimTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
mav->requestParameter(0, maxTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
mav->requestParameter(0, revTpl.arg(i+1));
QGC::SLEEP::usleep(5000);
if (mav) {
mav->getParamCommsMgr()->requestRcCalibrationParamsUpdate();
}
}
......
......@@ -48,7 +48,7 @@ QGCComboBox::QGCComboBox(QWidget *parent) :
connect(ui->editRemoveItemButton,SIGNAL(clicked()),this,SLOT(delButtonClicked()));
// Sending actions
connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(sendParameter()));
connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(setParamPending()));
connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectComponent(int)));
connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectParameter(int)));
//connect(ui->valueSlider, SIGNAL(valueChanged(int)), this, SLOT(setSliderValue(int)));
......@@ -108,15 +108,14 @@ void QGCComboBox::setActiveUAS(UASInterface* activeUas)
// Update current param value
//requestParameter();
// Set param info
QString text = uas->getParamManager()->getParamInfo(parameterName);
if (text != "")
{
QString text = uas->getParamDataModel()->getParamDescription(parameterName);
if (!text.isEmpty()) {
ui->infoLabel->setToolTip(text);
ui->infoLabel->show();
}
// Force-uncheck and hide label if no description is available
if (ui->editInfoCheckBox->isChecked())
{
if (ui->editInfoCheckBox->isChecked()) {
showInfo((text.length() > 0));
}
}
......@@ -147,27 +146,21 @@ void QGCComboBox::selectParameter(int paramIndex)
parameterName = ui->editSelectParamComboBox->itemText(paramIndex);
// Update min and max values if available
if (uas)
{
if (uas->getParamManager())
{
// Current value
//uas->getParamManager()->requestParameterUpdate(component, parameterName);
if (uas) {
UASParameterDataModel* dataModel = uas->getParamDataModel();
if (dataModel) {
// Minimum
if (uas->getParamManager()->isParamMinKnown(parameterName))
{
parameterMin = uas->getParamManager()->getParamMin(parameterName);
if (dataModel->isParamMinKnown(parameterName)) {
parameterMin = dataModel->getParamMin(parameterName);
}
// Maximum
if (uas->getParamManager()->isParamMaxKnown(parameterName))
{
parameterMax = uas->getParamManager()->getParamMax(parameterName);
if (dataModel->isParamMaxKnown(parameterName)) {
parameterMax = dataModel->getParamMax(parameterName);
}
// Description
QString text = uas->getParamManager()->getParamInfo(parameterName);
QString text = dataModel->getParamDescription(parameterName);
//ui->infoLabel->setText(text);
showInfo(!(text.length() > 0));
}
......@@ -240,24 +233,13 @@ void QGCComboBox::endEditMode()
emit editingFinished();
}
void QGCComboBox::sendParameter()
void QGCComboBox::setParamPending()
{
if (uas)
{
// Set value, param manager handles retransmission
if (uas->getParamManager())
{
qDebug() << "Sending param:" << parameterName << "to component" << component << "with a value of" << parameterValue;
uas->getParamManager()->setParameter(component, parameterName, parameterValue);
}
else
{
qDebug() << "UAS HAS NO PARAM MANAGER, DOING NOTHING";
}
if (uas) {
uas->getParamManager()->setPendingParam(component, parameterName, parameterValue);
}
else
{
qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
else {
qWarning() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
}
}
......
......@@ -23,8 +23,8 @@ public:
public slots:
void startEditMode();
void endEditMode();
/** @brief Send the parameter to the MAV */
void sendParameter();
/** @brief Queue parameter for sending to the MAV (add to pending list)*/
void setParamPending();
/** @brief Update the UI with the new parameter value */
void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, const QVariant value);
void writeSettings(QSettings& settings);
......
This diff is collapsed.
......@@ -23,8 +23,8 @@ public:
public slots:
void startEditMode();
void endEditMode();
/** @brief Send the parameter to the MAV */
void sendParameter();
/** @brief Queue parameter for sending to the MAV (add to pending list)*/
void setParamPending();
/** @brief Set the slider value as parameter value */
void setSliderValue(int sliderValue);
/** @brief Update the UI with the new parameter value */
......
......@@ -149,7 +149,7 @@ void UASListWidget::addUAS(UASInterface* uas)
QList<LinkInterface*>* x = uas->getLinks();
if (x->size())
{
LinkInterface* li = x->at(0);
LinkInterface* li = x->first();
// Find an existing QGroupBox for this LinkInterface or create a
// new one.
......
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