Browse Source

remove duplicate code

QGC4.4
treymarc 11 years ago
parent
commit
80f4f133a0
  1. 175
      src/uas/UAS.cc

175
src/uas/UAS.cc

@ -2551,125 +2551,76 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
parameters.insert(compId, new QMap<QString, QVariant>()); parameters.insert(compId, new QMap<QString, QVariant>());
} }
// Insert parameter into registry
if (parameters.value(compId)->contains(paramName)) {
parameters.value(compId)->remove(paramName);
}
QVariant param; QVariant param;
// Insert with correct type // Insert with correct type
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling. // TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
switch (rawValue.param_type) switch (rawValue.param_type) {
{ case MAV_PARAM_TYPE_REAL32:
case MAV_PARAM_TYPE_REAL32: if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
{ param = QVariant(paramValue.param_float);
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { } else {
param = QVariant(paramValue.param_float); param = QVariant(paramValue.param_float);
} }
else { break;
param = QVariant(paramValue.param_float); case MAV_PARAM_TYPE_UINT8:
} if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
parameters.value(compId)->insert(paramName, param); param = QVariant(QChar((unsigned char)paramValue.param_float));
// Emit change } else {
emit parameterChanged(uasId, compId, paramName, param); param = QVariant(QChar((quint8)paramValue.param_float));
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); }
// qDebug() << "RECEIVED PARAM:" << param; break;
} case MAV_PARAM_TYPE_INT8:
break; if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
case MAV_PARAM_TYPE_UINT8: param = QVariant(QChar((char)paramValue.param_float));
{ } else {
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { param = QVariant(QChar((qint8)paramValue.param_float));
param = QVariant(QChar((unsigned char)paramValue.param_float)); }
} break;
else { case MAV_PARAM_TYPE_INT16:
param = QVariant(QChar((quint8)paramValue.param_float)); if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
} param = QVariant((short)paramValue.param_float);
parameters.value(compId)->insert(paramName, param); } else {
// Emit change param = QVariant((qint16)paramValue.param_float);
emit parameterChanged(uasId, compId, paramName, param); }
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); break;
//qDebug() << "RECEIVED PARAM:" << param; case MAV_PARAM_TYPE_UINT16:
} if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
break; param = QVariant((unsigned short)paramValue.param_float);
case MAV_PARAM_TYPE_INT8: } else {
{ param = QVariant((quint16)paramValue.param_float);
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { }
param = QVariant(QChar((char)paramValue.param_float)); break;
} case MAV_PARAM_TYPE_UINT32:
else { if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant(QChar((qint8)paramValue.param_float)); param = QVariant((unsigned int)paramValue.param_float);
} } else {
parameters.value(compId)->insert(paramName, param); param = QVariant((quint32)paramValue.param_float);
// Emit change }
emit parameterChanged(uasId, compId, paramName, param); break;
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); case MAV_PARAM_TYPE_INT32:
//qDebug() << "RECEIVED PARAM:" << param; if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
} param = QVariant((int)paramValue.param_float);
break; } else {
case MAV_PARAM_TYPE_INT16: param = QVariant((qint32)paramValue.param_float);
{ }
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { break;
param = QVariant((short)paramValue.param_float); default:
} qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
else { return;
param = QVariant((qint16)paramValue.param_float);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
//qDebug() << "RECEIVED PARAM:" << param;
}
break;
case MAV_PARAM_TYPE_UINT16:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant((unsigned short)paramValue.param_float);
}
else {
param = QVariant((quint16)paramValue.param_float);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
//qDebug() << "RECEIVED PARAM:" << param;
}
break;
case MAV_PARAM_TYPE_UINT32:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant((unsigned int)paramValue.param_float);
}
else {
param = QVariant((quint32)paramValue.param_float);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
}
break;
case MAV_PARAM_TYPE_INT32:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant((int)paramValue.param_float);
}
else {
param = QVariant((qint32)paramValue.param_float);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
// qDebug() << "RECEIVED PARAM:" << param;
}
break;
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
} //switch (value.param_type) } //switch (value.param_type)
// We did not return a critical error, now insert parameter into registry
if (parameters.value(compId)->contains(paramName)) {
parameters.value(compId)->remove(paramName);
}
// add new values
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
} }
/** /**

Loading…
Cancel
Save