Commit c9a76441 authored by Lorenz Meier's avatar Lorenz Meier

Removed visibility / instance of message sender widget for now, fixed transmission of param widget

parent b5dde789
......@@ -420,10 +420,10 @@ void MainWindow::buildCommonWidgets()
if (!mavlinkSenderWidget)
{
mavlinkSenderWidget = new QDockWidget(tr("MAVLink Message Sender"), this);
mavlinkSenderWidget->setWidget( new QGCMAVLinkMessageSender(mavlink, this) );
mavlinkSenderWidget->setObjectName("MAVLINK_SENDER_DOCKWIDGET");
addTool(mavlinkSenderWidget, tr("MAVLink Sender"), Qt::RightDockWidgetArea);
// mavlinkSenderWidget = new QDockWidget(tr("MAVLink Message Sender"), this);
// mavlinkSenderWidget->setWidget( new QGCMAVLinkMessageSender(mavlink, this) );
// mavlinkSenderWidget->setObjectName("MAVLINK_SENDER_DOCKWIDGET");
// addTool(mavlinkSenderWidget, tr("MAVLink Sender"), Qt::RightDockWidgetArea);
}
//FIXME: memory of acceptList will never be freed again
......@@ -1420,7 +1420,7 @@ void MainWindow::loadViewState()
debugConsoleDockWidget->show();
logPlayerDockWidget->show();
mavlinkInspectorWidget->show();
mavlinkSenderWidget->show();
//mavlinkSenderWidget->show();
parametersDockWidget->show();
hsiDockWidget->hide();
headDown1DockWidget->hide();
......@@ -1457,7 +1457,7 @@ void MainWindow::loadViewState()
debugConsoleDockWidget->hide();
logPlayerDockWidget->hide();
mavlinkInspectorWidget->show();
mavlinkSenderWidget->show();
//mavlinkSenderWidget->show();
parametersDockWidget->hide();
hsiDockWidget->hide();
headDown1DockWidget->hide();
......@@ -1476,7 +1476,7 @@ void MainWindow::loadViewState()
debugConsoleDockWidget->hide();
logPlayerDockWidget->hide();
mavlinkInspectorWidget->hide();
mavlinkSenderWidget->hide();
//mavlinkSenderWidget->hide();
parametersDockWidget->hide();
hsiDockWidget->hide();
headDown1DockWidget->hide();
......
......@@ -58,15 +58,17 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
tree = new QTreeWidget(this);
statusLabel = new QLabel();
statusLabel->setAutoFillBackground(true);
tree->setColumnWidth(0, 150);
tree->setColumnWidth(0, 175);
// Set tree widget as widget onto this component
QGridLayout* horizontalLayout;
//form->setAutoFillBackground(false);
horizontalLayout = new QGridLayout(this);
horizontalLayout->setSpacing(6);
horizontalLayout->setHorizontalSpacing(6);
horizontalLayout->setVerticalSpacing(6);
horizontalLayout->setMargin(0);
horizontalLayout->setSizeConstraint(QLayout::SetMinimumSize);
//horizontalLayout->setSizeConstraint(QLayout::SetMinimumSize);
horizontalLayout->setSizeConstraint( QLayout::SetFixedSize );
// Parameter tree
horizontalLayout->addWidget(tree, 0, 0, 1, 3);
......@@ -113,6 +115,12 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
connect(readButton, SIGNAL(clicked()), this, SLOT(readParameters()));
horizontalLayout->addWidget(readButton, 3, 2);
// Set correct vertical scaling
horizontalLayout->setRowStretch(0, 100);
horizontalLayout->setRowStretch(1, 10);
horizontalLayout->setRowStretch(2, 10);
horizontalLayout->setRowStretch(3, 10);
// Set layout
this->setLayout(horizontalLayout);
......@@ -135,6 +143,9 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
connect(this, SIGNAL(requestParameter(int,QString)), uas, SLOT(requestParameter(int,QString)));
connect(this, SIGNAL(requestParameter(int,int)), uas, SLOT(requestParameter(int,int)));
connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick()));
// Get parameters
if (uas) mav->requestParameters();
}
void QGCParamWidget::loadSettings()
......@@ -431,7 +442,9 @@ 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.toDouble()).arg(missCount).arg(paramCount));
QString val = QString("%1").arg(value.toFloat(), 5, 'f', 1, QChar(' '));
//statusLabel->setText(tr("OK: %1 %2 #%3/%4, %5 miss").arg(parameterName).arg(val).arg(paramId+1).arg(paramCount).arg(missCount));
statusLabel->setText(tr("OK: %1 %2 (%3/%4)").arg(parameterName).arg(val).arg(paramCount-missCount).arg(paramCount));
}
// Check if last parameter was received
......@@ -444,6 +457,9 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
{
transmissionMissingPackets.value(key)->clear();
}
// Expand visual tree
tree->expandItem(tree->topLevelItem(0));
}
}
......@@ -564,7 +580,7 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
//tree->expandAll();
}
// Reset background color
parameterItem->setBackground(0, QBrush(QColor(0, 0, 0)));
parameterItem->setBackground(0, Qt::NoBrush);
parameterItem->setBackground(1, Qt::NoBrush);
// Add tooltip
QString tooltipFormat;
......@@ -614,7 +630,6 @@ void QGCParamWidget::requestParameterList()
// Set status text
statusLabel->setText(tr("Requested param list.. waiting"));
// Request twice as mean of forward error correction
mav->requestParameters();
}
......@@ -634,9 +649,11 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column)
if (map) {
QString str = current->data(0, Qt::DisplayRole).toString();
QVariant value = current->data(1, Qt::DisplayRole);
qDebug() << "CHANGED PARAM:" << value;
// Set parameter on changed list to be transmitted to MAV
statusLabel->setText(tr("Changed Param %1:%2: %3").arg(key).arg(str).arg(value.toDouble()));
QPalette pal = statusLabel->palette();
pal.setColor(backgroundRole(), QGC::colorOrange);
statusLabel->setPalette(pal);
statusLabel->setText(tr("Transmit pend. %1:%2: %3").arg(key).arg(str).arg(value.toFloat(), 5, 'f', 1, QChar(' ')));
//qDebug() << "PARAM CHANGED: COMP:" << key << "KEY:" << str << "VALUE:" << value;
// Changed values list
if (map->contains(str)) map->remove(str);
......
......@@ -121,6 +121,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid)
*u = field->data(1, Qt::DisplayRole).toChar().toAscii();
}
break;
case MAVLINK_TYPE_INT16_T:
case MAVLINK_TYPE_UINT16_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
......@@ -140,205 +141,84 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid)
*u = field->data(1, Qt::DisplayRole).toUInt();
}
break;
// case MAVLINK_TYPE_INT8_T:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// int8_t* nums = (int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// if (field->data(1, DisplayRole).toString().split(" ").size() > j)
// {
// nums[j] = field->data(1, DisplayRole).toString().split(" ").at(j).toInt();
// }
// }
// item->setData(2, Qt::DisplayRole, QString("int8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// int8_t n = *((int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "int8_t");
// item->setData(1, Qt::DisplayRole, n);
// }
// break;
// case MAVLINK_TYPE_UINT16_T:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// uint16_t* nums = (uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("uint16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// uint16_t n = *((uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "uint16_t");
// item->setData(1, Qt::DisplayRole, n);
// }
// break;
// case MAVLINK_TYPE_INT16_T:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// int16_t* nums = (int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("int16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// int16_t n = *((int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "int16_t");
// item->setData(1, Qt::DisplayRole, n);
// }
// break;
// case MAVLINK_TYPE_UINT32_T:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// uint32_t* nums = (uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("uint32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// float n = *((uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "uint32_t");
// item->setData(1, Qt::DisplayRole, n);
// }
// break;
// case MAVLINK_TYPE_INT32_T:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// int32_t* nums = (int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("int32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// int32_t n = *((int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "int32_t");
// item->setData(1, Qt::DisplayRole, n);
// }
// break;
// case MAVLINK_TYPE_FLOAT:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// float* nums = (float*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("float[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// float f = *((float*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "float");
// item->setData(1, Qt::DisplayRole, f);
// }
// break;
// case MAVLINK_TYPE_DOUBLE:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// double* nums = (double*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("double[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// double f = *((double*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "double");
// item->setData(1, Qt::DisplayRole, f);
// }
// break;
// case MAVLINK_TYPE_UINT64_T:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// uint64_t* nums = (uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("uint64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "uint64_t");
// item->setData(1, Qt::DisplayRole, (quint64) n);
// }
// break;
// case MAVLINK_TYPE_INT64_T:
// if (messageInfo[msgid].fields[fieldid].array_length > 0)
// {
// int64_t* nums = (int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// // Enforce null termination
// QString tmp("%1, ");
// QString string;
// for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
// {
// string += tmp.arg(nums[j]);
// }
// item->setData(2, Qt::DisplayRole, QString("int64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
// item->setData(1, Qt::DisplayRole, string);
// }
// else
// {
// // Single value
// int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
// item->setData(2, Qt::DisplayRole, "int64_t");
// item->setData(1, Qt::DisplayRole, (qint64) n);
// }
// break;
case MAVLINK_TYPE_INT32_T:
case MAVLINK_TYPE_UINT32_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
int32_t* nums = reinterpret_cast<int32_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
{
if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
{
nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toUInt();
}
}
}
else
{
// Single value
int32_t* u = reinterpret_cast<int32_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
*u = field->data(1, Qt::DisplayRole).toUInt();
}
break;
case MAVLINK_TYPE_INT64_T:
case MAVLINK_TYPE_UINT64_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
int64_t* nums = reinterpret_cast<int64_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
{
if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
{
nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toULongLong();
}
}
}
else
{
// Single value
int64_t* u = reinterpret_cast<int64_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
*u = field->data(1, Qt::DisplayRole).toULongLong();
}
break;
case MAVLINK_TYPE_FLOAT:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
float* nums = reinterpret_cast<float*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
{
if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
{
nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toFloat();
}
}
}
else
{
// Single value
float* u = reinterpret_cast<float*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
*u = field->data(1, Qt::DisplayRole).toFloat();
}
break;
case MAVLINK_TYPE_DOUBLE:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
double* nums = reinterpret_cast<double*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
{
if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
{
nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toDouble();
}
}
}
else
{
// Single value
double* u = reinterpret_cast<double*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
*u = field->data(1, Qt::DisplayRole).toDouble();
}
break;
}
}
......
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