|
|
@ -2554,76 +2554,110 @@ 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: |
|
|
|
{ |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
case MAV_PARAM_TYPE_REAL32: |
|
|
|
param = QVariant(paramValue.param_float); |
|
|
|
{ |
|
|
|
} else { |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
param = QVariant(paramValue.param_float); |
|
|
|
param = QVariant(paramValue.param_float); |
|
|
|
} |
|
|
|
} |
|
|
|
break; |
|
|
|
else { |
|
|
|
case MAV_PARAM_TYPE_UINT8: |
|
|
|
param = QVariant(paramValue.param_float); |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
} |
|
|
|
param = QVariant(QChar((unsigned char)paramValue.param_float)); |
|
|
|
parameters.value(compId)->insert(paramName, param); |
|
|
|
} else { |
|
|
|
// Emit change
|
|
|
|
param = QVariant(QChar((quint8)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_INT8: |
|
|
|
} |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
break; |
|
|
|
param = QVariant(QChar((char)paramValue.param_float)); |
|
|
|
case MAV_PARAM_TYPE_UINT8: |
|
|
|
} else { |
|
|
|
{ |
|
|
|
param = QVariant(QChar((qint8)paramValue.param_float)); |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
} |
|
|
|
param = QVariant(QChar((unsigned char)paramValue.param_float)); |
|
|
|
break; |
|
|
|
} |
|
|
|
case MAV_PARAM_TYPE_INT16: |
|
|
|
else { |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
param = QVariant(QChar((unsigned char)paramValue.param_uint8)); |
|
|
|
param = QVariant((short)paramValue.param_float); |
|
|
|
} |
|
|
|
} else { |
|
|
|
parameters.value(compId)->insert(paramName, param); |
|
|
|
param = QVariant((qint16)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_UINT16: |
|
|
|
//qDebug() << "RECEIVED PARAM:" << param;
|
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
} |
|
|
|
param = QVariant((unsigned short)paramValue.param_float); |
|
|
|
break; |
|
|
|
} else { |
|
|
|
case MAV_PARAM_TYPE_INT8: |
|
|
|
param = QVariant((quint16)paramValue.param_float); |
|
|
|
{ |
|
|
|
} |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
break; |
|
|
|
param = QVariant(QChar((char)paramValue.param_float)); |
|
|
|
case MAV_PARAM_TYPE_UINT32: |
|
|
|
} |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
else { |
|
|
|
param = QVariant((unsigned int)paramValue.param_float); |
|
|
|
param = QVariant(QChar((char)paramValue.param_int8)); |
|
|
|
} else { |
|
|
|
} |
|
|
|
param = QVariant((quint32)paramValue.param_float); |
|
|
|
parameters.value(compId)->insert(paramName, param); |
|
|
|
} |
|
|
|
// Emit change
|
|
|
|
break; |
|
|
|
emit parameterChanged(uasId, compId, paramName, param); |
|
|
|
case MAV_PARAM_TYPE_INT32: |
|
|
|
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
//qDebug() << "RECEIVED PARAM:" << param;
|
|
|
|
param = QVariant((int)paramValue.param_float); |
|
|
|
} |
|
|
|
} else { |
|
|
|
break; |
|
|
|
param = QVariant((qint32)paramValue.param_float); |
|
|
|
case MAV_PARAM_TYPE_INT16: |
|
|
|
} |
|
|
|
{ |
|
|
|
break; |
|
|
|
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { |
|
|
|
default: |
|
|
|
param = QVariant((short)paramValue.param_float); |
|
|
|
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type; |
|
|
|
} |
|
|
|
return; |
|
|
|
else { |
|
|
|
|
|
|
|
param = QVariant(paramValue.param_int16); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
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(paramValue.param_uint32); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
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(paramValue.param_int32); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
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); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
/**
|
|
|
|