Commit 359faf28 authored by lm's avatar lm
Browse files

Folder structure cleanup, added APM tooltips

parent 0f7c4379
This diff is collapsed.
......@@ -66,10 +66,12 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
onboardParams.insert("PID_ROLL_K_P", 0.5f);
onboardParams.insert("PID_PITCH_K_P", 0.5f);
onboardParams.insert("PID_YAW_K_P", 0.5f);
onboardParams.insert("PID_XY_K_P", 0.5f);
onboardParams.insert("PID_XY_K_P", 100.0f);
onboardParams.insert("PID_ALT_K_P", 0.5f);
onboardParams.insert("SYS_TYPE", 1);
onboardParams.insert("SYS_ID", systemId);
onboardParams.insert("RC4_REV", 0);
onboardParams.insert("RC5_REV", 1);
// Comments on the variables can be found in the header file
......
......@@ -68,7 +68,7 @@ void MAVLinkSimulationMAV::mainloop()
// 1 Hz execution
if (timer1Hz <= 0) {
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, MAV_MODE_GUIDED, MAV_FLIGHT_MODE_AUTO_MISSION, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_MODE_GUIDED, MAV_FLIGHT_MODE_AUTO_MISSION, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg);
......
......@@ -4,6 +4,7 @@
#include <QWidget>
#include <QMap>
#include <QTimer>
#include <QVariant>
class UASInterface;
......@@ -16,10 +17,10 @@ public:
QList<QString> getParameterNames(int component) const {
return parameters.value(component)->keys();
}
QList<float> getParameterValues(int component) const {
QList<QVariant> getParameterValues(int component) const {
return parameters.value(component)->values();
}
float getParameterValue(int component, const QString& parameter) const {
QVariant getParameterValue(int component, const QString& parameter) const {
return parameters.value(component)->value(parameter);
}
......@@ -29,23 +30,23 @@ public:
virtual void requestParameterUpdate(int component, const QString& parameter) = 0;
signals:
void parameterChanged(int component, QString parameter, float value);
void parameterChanged(int component, int parameterIndex, float value);
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, float value) = 0;
virtual void setParameter(int component, QString parameterName, QVariant value) = 0;
/** @brief Request list of parameters from MAV */
virtual void requestParameterList() = 0;
protected:
UASInterface* mav; ///< The MAV this widget is controlling
QMap<int, QMap<QString, float>* > changedValues; ///< Changed values
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
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, float>* > transmissionMissingWriteAckPackets; ///< Missing write ACK 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?
......
......@@ -743,21 +743,74 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QString parameterName = QString(bytes);
int component = message.compid;
float val = value.param_value;
mavlink_param_union_t val;
val.param_float = value.param_value;
// Convert to machine order if necessary
//#if MAVLINK_NEED_BYTE_SWAP
// buffer[bindex] = (b>>24)&0xff;
// buffer[bindex+1] = (b>>16)&0xff;
// buffer[bindex+2] = (b>>8)&0xff;
// buffer[bindex+3] = (b & 0xff);
//#else
// Insert component if necessary
if (!parameters.contains(component))
{
parameters.insert(component, new QMap<QString, float>());
parameters.insert(component, new QMap<QString, QVariant>());
}
// Insert parameter into registry
if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
parameters.value(component)->insert(parameterName, val);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val);
// Insert with correct type
switch (value.param_type)
{
case MAV_DATA_TYPE_FLOAT:
parameters.value(component)->insert(parameterName, val.param_float);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_float);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_float);
break;/*
case MAV_DATA_TYPE_UINT8:
parameters.value(component)->insert(parameterName, val.param_uint8);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint8);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint8);
break;
case MAV_DATA_TYPE_INT8:
parameters.value(component)->insert(parameterName, val.param_int8);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int8);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int8);
break;
case MAV_DATA_TYPE_UINT16:
parameters.value(component)->insert(parameterName, val.param_uint16);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint16);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint16);
break;
case MAV_DATA_TYPE_INT16:
parameters.value(component)->insert(parameterName, val.param_int16);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int16);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int16);
break;*/
case MAV_DATA_TYPE_UINT32:
parameters.value(component)->insert(parameterName, val.param_uint32);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint32);
break;
case MAV_DATA_TYPE_INT32:
parameters.value(component)->insert(parameterName, val.param_int32);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int32);
break;
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
}
}
break;
case MAVLINK_MSG_ID_COMMAND_ACK:
......@@ -1868,13 +1921,35 @@ void UAS::enableExtra3Transmission(int rate)
* @param id Name of the parameter
* @param value Parameter value
*/
void UAS::setParameter(const int component, const QString& id, const float value)
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
{
if (!id.isNull())
{
mavlink_message_t msg;
mavlink_param_set_t p;
p.param_value = value;
mavlink_param_union_t union_value;
// Assign correct value based on QVariant
switch (value.type())
{
case QVariant::Int:
union_value.param_int32 = value.toInt();
p.param_type = MAV_DATA_TYPE_INT32;
break;
case QVariant::UInt:
union_value.param_uint32 = value.toUInt();
p.param_type = MAV_DATA_TYPE_UINT32;
break;
case QMetaType::Float:
union_value.param_float = value.toFloat();
p.param_type = MAV_DATA_TYPE_FLOAT;
break;
default:
qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
return;
}
p.param_value = union_value.param_float;
p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)component;
......
......@@ -200,7 +200,7 @@ protected: //COMMENTS FOR TEST UNIT
QImage image; ///< Image data of last completely transmitted image
quint64 imageStart;
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else
......@@ -459,7 +459,7 @@ public slots:
void requestParameter(int component, int parameter);
/** @brief Set a system parameter */
void setParameter(const int component, const QString& id, const float value);
void setParameter(const int component, const QString& id, const QVariant& value);
/** @brief Write parameters to permanent storage */
void writeParametersToStorage();
......
......@@ -255,7 +255,7 @@ public slots:
* @warning The length of the ID string is limited by the MAVLink format! Take care to not exceed it
* @param value Value of the parameter, IEEE 754 single precision floating point
*/
virtual void setParameter(const int component, const QString& id, const float value) = 0;
virtual void setParameter(const int component, const QString& id, const QVariant& value) = 0;
/**
* @brief Add a link to the list of current links
......@@ -395,8 +395,8 @@ signals:
void waypointSelected(int uasId, int id);
void waypointReached(UASInterface* uas, int id);
void autoModeChanged(bool autoMode);
void parameterChanged(int uas, int component, QString parameterName, float value);
void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, float value);
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
void patternDetected(int uasId, QString patternPath, float confidence, bool detected);
void letterDetected(int uasId, QString letter, float confidence, bool detected);
/**
......
......@@ -123,11 +123,11 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
tree->setExpandsOnDoubleClick(true);
// Connect signals/slots
connect(this, SIGNAL(parameterChanged(int,QString,float)), mav, SLOT(setParameter(int,QString,float)));
connect(this, SIGNAL(parameterChanged(int,QString,QVariant)), mav, SLOT(setParameter(int,QString,QVariant)));
connect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)), this, SLOT(parameterItemChanged(QTreeWidgetItem*,int)));
// New parameters from UAS
connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,float)), this, SLOT(addParameter(int,int,int,int,QString,float)));
connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(addParameter(int,int,int,int,QString,QVariant)));
// Connect retransmission guard
connect(this, SIGNAL(requestParameter(int,int)), uas, SLOT(requestParameter(int,int)));
......@@ -150,7 +150,7 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin
{
QDir appDir = QDir::current();
appDir.cd("files/parameter_tooltips");
QString fileName = QString("MAV_AUTOPILOT_%1-MAV_TYPE_%2.csv").arg(autopilot).arg(airframe);
QString fileName = QString("MAV_AUTOPILOT_%1-MAV_TYPE_%2.txt").arg(autopilot).arg(airframe);
QString filePath = appDir.filePath(fileName);
QFile paramMetaFile(filePath);
......@@ -168,15 +168,23 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin
QTextStream in(&paramMetaFile);
// First line is header
// there might be more lines, but the first
// line is assumed to be at least header
QString header = in.readLine();
// Ignore top-level comment lines
while (header.startsWith('#') || header.startsWith('/') || header.startsWith('='))
{
header = in.readLine();
}
bool charRead = false;
QString separator = "";
QList<QChar> sepCandidates;
sepCandidates << '\t';
sepCandidates << ',';
sepCandidates << ';';
sepCandidates << ' ';
//sepCandidates << ' ';
sepCandidates << '~';
sepCandidates << '|';
......@@ -203,6 +211,15 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin
}
}
bool stripFirstSeparator = false;
bool stripLastSeparator = false;
// Figure out if the lines start with the separator (e.g. wiki syntax)
if (header.startsWith(separator)) stripFirstSeparator = true;
// Figure out if the lines end with the separator (e.g. wiki syntax)
if (header.endsWith(separator)) stripLastSeparator = true;
QString out = separator;
out.replace("\t", "<tab>");
qDebug() << " Separator: \"" << out << "\"";
......@@ -214,6 +231,14 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin
{
QString line = in.readLine();
//qDebug() << "LINE PRE-STRIP" << line;
// Strip separtors if necessary
if (stripFirstSeparator) line.remove(0, separator.length());
if (stripLastSeparator) line.remove(line.length()-separator.length(), line.length()-1);
//qDebug() << "LINE POST-STRIP" << line;
// Keep empty parts here - we still have to act on them
QStringList parts = line.split(separator, QString::KeepEmptyParts);
......@@ -281,11 +306,11 @@ void QGCParamWidget::addComponent(int uas, int component, QString componentName)
tree->update();
// Create map in parameters
if (!parameters.contains(component)) {
parameters.insert(component, new QMap<QString, float>());
parameters.insert(component, new QMap<QString, QVariant>());
}
// Create map in changed parameters
if (!changedValues.contains(component)) {
changedValues.insert(component, new QMap<QString, float>());
changedValues.insert(component, new QMap<QString, QVariant>());
}
}
}
......@@ -295,7 +320,7 @@ void QGCParamWidget::addComponent(int uas, int component, QString componentName)
* @param component id of the component
* @param parameterName human friendly name of the parameter
*/
void QGCParamWidget::addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, float value)
void QGCParamWidget::addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value)
{
addParameter(uas, component, parameterName, value);
......@@ -346,7 +371,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
bool writeMismatch = false;
//bool lastWritten = false;
// Mark this parameter as received in write ACK list
QMap<QString, float>* map = transmissionMissingWriteAckPackets.value(component);
QMap<QString, QVariant>* map = transmissionMissingWriteAckPackets.value(component);
if (map && map->contains(parameterName))
{
justWritten = true;
......@@ -378,7 +403,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
statusLabel->setPalette(pal);
} else if (justWritten && !writeMismatch)
{
statusLabel->setText(tr("SUCCESS: Wrote %2 (#%1/%4): %3").arg(paramId+1).arg(parameterName).arg(value).arg(paramCount));
statusLabel->setText(tr("SUCCESS: Wrote %2 (#%1/%4): %3").arg(paramId+1).arg(parameterName).arg(value.toDouble()).arg(paramCount));
QPalette pal = statusLabel->palette();
pal.setColor(backgroundRole(), QGC::colorGreen);
statusLabel->setPalette(pal);
......@@ -388,7 +413,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
QPalette pal = statusLabel->palette();
pal.setColor(backgroundRole(), QGC::colorRed);
statusLabel->setPalette(pal);
statusLabel->setText(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(parameterName).arg(map->value(parameterName)).arg(value));
statusLabel->setText(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(parameterName).arg(map->value(parameterName).toDouble()).arg(value.toDouble()));
}
else
{
......@@ -404,7 +429,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
pal.setColor(backgroundRole(), QGC::colorGreen);
statusLabel->setPalette(pal);
}
statusLabel->setText(tr("Got %2 (#%1/%5): %3 (%4 missing)").arg(paramId+1).arg(parameterName).arg(value).arg(missCount).arg(paramCount));
statusLabel->setText(tr("Got %2 (#%1/%5): %3 (%4 missing)").arg(paramId+1).arg(parameterName).arg(value.toDouble()).arg(missCount).arg(paramCount));
}
// Check if last parameter was received
......@@ -425,7 +450,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
* @param component id of the component
* @param parameterName human friendly name of the parameter
*/
void QGCParamWidget::addParameter(int uas, int component, QString parameterName, float value)
void QGCParamWidget::addParameter(int uas, int component, QString parameterName, QVariant value)
{
Q_UNUSED(uas);
// Reference to item in tree
......@@ -464,7 +489,8 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
{
QString parent = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty);
QMap<QString, QTreeWidgetItem*>* compParamGroups = paramGroups.value(component);
if (!compParamGroups->contains(parent)) {
if (!compParamGroups->contains(parent))
{
// Insert group item
QStringList glist;
glist.append(parent);
......@@ -479,7 +505,8 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
for (int i = 0; i < parentItem->childCount(); i++) {
QTreeWidgetItem* child = parentItem->child(i);
QString key = child->data(0, Qt::DisplayRole).toString();
if (key == parameterName) {
if (key == parameterName)
{
//qDebug() << "UPDATED CHILD";
parameterItem = child;
parameterItem->setData(1, Qt::DisplayRole, value);
......@@ -492,7 +519,7 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
// Insert parameter into map
QStringList plist;
plist.append(parameterName);
plist.append(QString::number(value));
plist.append(QString::number(value.toDouble()));
// CREATE PARAMETER ITEM
parameterItem = new QTreeWidgetItem(plist);
// CONFIGURE PARAMETER ITEM
......@@ -523,7 +550,7 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
// Insert parameter into map
QStringList plist;
plist.append(parameterName);
plist.append(QString::number(value));
plist.append(QString::number(value.toDouble()));
// CREATE PARAMETER ITEM
parameterItem = new QTreeWidgetItem(plist);
// CONFIGURE PARAMETER ITEM
......@@ -589,9 +616,9 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column)
// Parent is now top-level component
int key = components->key(parent);
if (!changedValues.contains(key)) {
changedValues.insert(key, new QMap<QString, float>());
changedValues.insert(key, new QMap<QString, QVariant>());
}
QMap<QString, float>* map = changedValues.value(key, NULL);
QMap<QString, QVariant>* map = changedValues.value(key, NULL);
if (map) {
bool ok;
QString str = current->data(0, Qt::DisplayRole).toString();
......@@ -636,16 +663,17 @@ void QGCParamWidget::saveParameters()
in << "# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)\n";
// Iterate through all components, through all parameters and emit them
QMap<int, QMap<QString, float>*>::iterator i;
QMap<int, QMap<QString, QVariant>*>::iterator i;
for (i = parameters.begin(); i != parameters.end(); ++i) {
// Iterate through the parameters of the component
int compid = i.key();
QMap<QString, float>* comp = i.value();
QMap<QString, QVariant>* comp = i.value();
{
QMap<QString, float>::iterator j;
for (j = comp->begin(); j != comp->end(); ++j) {
QMap<QString, QVariant>::iterator j;
for (j = comp->begin(); j != comp->end(); ++j)
{
QString paramValue("%1");
paramValue = paramValue.arg(j.value(), 25, 'g', 12);
paramValue = paramValue.arg(j.value().toDouble(), 25, 'g', 12);
in << mav->getUASID() << "\t" << compid << "\t" << j.key() << "\t" << paramValue << "\n";
in.flush();
}
......@@ -687,7 +715,7 @@ void QGCParamWidget::loadParameters()
if (changed) {
// Create changed values data structure if necessary
if (!changedValues.contains(wpParams.at(1).toInt())) {
changedValues.insert(wpParams.at(1).toInt(), new QMap<QString, float>());
changedValues.insert(wpParams.at(1).toInt(), new QMap<QString, QVariant>());
}
// Add to changed values
......@@ -759,7 +787,7 @@ void QGCParamWidget::retransmissionGuardTick()
// Re-request at maximum retransmissionBurstRequestSize parameters at once
// to prevent link flooding
QMap<int, QMap<QString, float>*>::iterator i;
QMap<int, QMap<QString, QVariant>*>::iterator i;
for (i = parameters.begin(); i != parameters.end(); ++i) {
// Iterate through the parameters of the component
int component = i.key();
......@@ -786,12 +814,12 @@ void QGCParamWidget::retransmissionGuardTick()
QList<int> writeKeys = transmissionMissingWriteAckPackets.keys();
foreach (int component, writeKeys) {
int count = 0;
QMap <QString, float>* missingParams = transmissionMissingWriteAckPackets.value(component);
QMap <QString, QVariant>* missingParams = transmissionMissingWriteAckPackets.value(component);
foreach (QString key, missingParams->keys()) {
if (count < retransmissionBurstRequestSize) {
// Re-request write operation
emit parameterChanged(component, key, missingParams->value(key));
statusLabel->setText(tr("Requested rewrite of: %1: %2").arg(key).arg(missingParams->value(key)));
statusLabel->setText(tr("Requested rewrite of: %1: %2").arg(key).arg(missingParams->value(key).toDouble()));
count++;
} else {
break;
......@@ -819,13 +847,24 @@ void QGCParamWidget::requestParameterUpdate(int component, const QString& parame
* @param parameterName name of the parameter, as delivered by the system
* @param value value of the parameter
*/
void QGCParamWidget::setParameter(int component, QString parameterName, float value)
void QGCParamWidget::setParameter(int component, QString parameterName, QVariant value)
{
if (paramMin.contains(parameterName) && value.toDouble() < paramMin.value(parameterName))
{
statusLabel->setText(tr("REJ. %1 < min").arg(value.toDouble()));
return;
}
if (paramMax.contains(parameterName) && value.toDouble() > paramMax.value(parameterName))
{
statusLabel->setText(tr("REJ. %1 > max").arg(value.toDouble()));
return;
}
emit parameterChanged(component, parameterName, value);
// Wait for parameter to be written back
// mark it therefore as missing
if (!transmissionMissingWriteAckPackets.contains(component)) {
transmissionMissingWriteAckPackets.insert(component, new QMap<QString, float>());
if (!transmissionMissingWriteAckPackets.contains(component))
{
transmissionMissingWriteAckPackets.insert(component, new QMap<QString, QVariant>());
}
// Insert it in missing write ACK list
......@@ -848,13 +887,13 @@ void QGCParamWidget::setParameters()
{
// Iterate through all components, through all parameters and emit them
int parametersSent = 0;
QMap<int, QMap<QString, float>*>::iterator i;
QMap<int, QMap<QString, QVariant>*>::iterator i;
for (i = changedValues.begin(); i != changedValues.end(); ++i) {
// Iterate through the parameters of the component
int compid = i.key();
QMap<QString, float>* comp = i.value();
QMap<QString, QVariant>* comp = i.value();
{
QMap<QString, float>::iterator j;
QMap<QString, QVariant>::iterator j;
for (j = comp->begin(); j != comp->end(); ++j) {
setParameter(compid, j.key(), j.value());
parametersSent++;
......
......@@ -52,22 +52,22 @@ public:
UASInterface* getUAS();
signals:
/** @brief A parameter was changed in the widget, NOT onboard */
void parameterChanged(int component, QString parametername, float value);
void parameterChanged(int component, QString parametername, QVariant value);
/** @brief Request a single parameter */
void requestParameter(int component, int 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, float value);
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, float value);
void addParameter(int uas, 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, float value);
void setParameter(int component, QString parameterName, QVariant value);
/** @brief Set all parameters, changes the value in RAM of MAV */
void setParameters();
/** @brief Write the current parameters to permanent storage (EEPROM/HDD) */
......@@ -96,9 +96,9 @@ protected:
// Tooltip data structures
QMap<QString, QString> paramToolTips; ///< Tooltip values
// Min / Default / Max data structures
QMap<QString, float> paramMin; ///< Minimum param values
QMap<QString, float> paramDefault; ///< Default param values
QMap<QString, float> paramMax; ///< Minimum param values
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);
......
......@@ -69,7 +69,7 @@ void UASControlWidget::setUAS(UASInterface* uas)
{
if (this->uas != 0) {
UASInterface* oldUAS = UASManager::instance()->getUASForId(this->uas);
disconnect(ui.controlButton, SIGNAL(clicked()), oldUAS, SLOT(enable_motors()));
disconnect(ui.controlButton, SIGNAL(clicked()), oldUAS, SLOT(armSystem()));
disconnect(ui.liftoffButton, SIGNAL(clicked()), oldUAS, SLOT(launch()));
disconnect(ui.landButton, SIGNAL(clicked()), oldUAS, SLOT(home()));
disconnect(ui.shutdownButton, SIGNAL(clicked()), oldUAS, SLOT(shutdown()));
......
Supports Markdown
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