Commit ec799d44 authored by treymarc's avatar treymarc

fix value reading, only real32 was correct.

parent cbb366b6
...@@ -2583,7 +2583,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2583,7 +2583,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
param = QVariant(QChar((unsigned char)paramValue.param_float)); param = QVariant(QChar((unsigned char)paramValue.param_float));
} }
else { else {
param = QVariant(QChar((unsigned char)paramValue.param_uint8)); param = QVariant(QChar((uint8_t)paramValue.param_float));
} }
parameters.value(compId)->insert(paramName, param); parameters.value(compId)->insert(paramName, param);
// Emit change // Emit change
...@@ -2598,7 +2598,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2598,7 +2598,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
param = QVariant(QChar((char)paramValue.param_float)); param = QVariant(QChar((char)paramValue.param_float));
} }
else { else {
param = QVariant(QChar((char)paramValue.param_int8)); param = QVariant(QChar((int8_t)paramValue.param_float));
} }
parameters.value(compId)->insert(paramName, param); parameters.value(compId)->insert(paramName, param);
// Emit change // Emit change
...@@ -2613,7 +2613,22 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2613,7 +2613,22 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
param = QVariant((short)paramValue.param_float); param = QVariant((short)paramValue.param_float);
} }
else { else {
param = QVariant(paramValue.param_int16); param = QVariant((int16_t)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((uint16_t)paramValue.param_float);
} }
parameters.value(compId)->insert(paramName, param); parameters.value(compId)->insert(paramName, param);
// Emit change // Emit change
...@@ -2628,7 +2643,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2628,7 +2643,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
param = QVariant((unsigned int)paramValue.param_float); param = QVariant((unsigned int)paramValue.param_float);
} }
else { else {
param = QVariant(paramValue.param_uint32); param = QVariant((uint32_t)paramValue.param_float);
} }
parameters.value(compId)->insert(paramName, param); parameters.value(compId)->insert(paramName, param);
// Emit change // Emit change
...@@ -2642,7 +2657,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2642,7 +2657,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
param = QVariant((int)paramValue.param_float); param = QVariant((int)paramValue.param_float);
} }
else { else {
param = QVariant(paramValue.param_int32); param = QVariant((int32_t)paramValue.param_float);
} }
parameters.value(compId)->insert(paramName, param); parameters.value(compId)->insert(paramName, param);
// Emit change // Emit change
......
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