Commit fbd6ad0c authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #156 from jjhall89/mavParamType

Replaced MAVLINK_TYPE with MAV_PARAM_TYPE where neccessary.
parents 813bae19 512a339e
......@@ -785,7 +785,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
if (j != 5) {
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), MAVLINK_TYPE_FLOAT, onboardParams.size(), j);
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), MAV_PARAM_TYPE_REAL32, onboardParams.size(), j);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -816,7 +816,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams.insert(key, set.param_value);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, MAV_PARAM_TYPE_REAL32, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -839,7 +839,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAV_PARAM_TYPE_REAL32, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -853,7 +853,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAV_PARAM_TYPE_REAL32, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......
......@@ -772,7 +772,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Insert with correct type
switch (value.param_type)
{
case MAVLINK_TYPE_FLOAT:
case MAV_PARAM_TYPE_REAL32:
{
// Variant
QVariant param(val.param_float);
......@@ -783,7 +783,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
qDebug() << "RECEIVED PARAM:" << param;
}
break;
case MAVLINK_TYPE_UINT32_T:
case MAV_PARAM_TYPE_UINT32:
{
// Variant
QVariant param(val.param_uint32);
......@@ -794,7 +794,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
qDebug() << "RECEIVED PARAM:" << param;
}
break;
case MAVLINK_TYPE_INT32_T:
case MAV_PARAM_TYPE_INT32:
{
// Variant
QVariant param(val.param_int32);
......@@ -2001,15 +2001,15 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
{
case QVariant::Int:
union_value.param_int32 = value.toInt();
p.param_type = MAVLINK_TYPE_INT32_T;
p.param_type = MAV_PARAM_TYPE_INT32;
break;
case QVariant::UInt:
union_value.param_uint32 = value.toUInt();
p.param_type = MAVLINK_TYPE_UINT32_T;
p.param_type = MAV_PARAM_TYPE_UINT32;
break;
case QMetaType::Float:
union_value.param_float = value.toFloat();
p.param_type = MAVLINK_TYPE_FLOAT;
p.param_type = MAV_PARAM_TYPE_REAL32;
break;
default:
qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
......
......@@ -724,15 +724,15 @@ void QGCParamWidget::saveParameters()
{
case QVariant::Int:
paramValue = paramValue.arg(j.value().toInt());
paramType = paramType.arg(MAVLINK_TYPE_INT32_T);
paramType = paramType.arg(MAV_PARAM_TYPE_INT32);
break;
case QVariant::UInt:
paramValue = paramValue.arg(j.value().toUInt());
paramType = paramType.arg(MAVLINK_TYPE_UINT32_T);
paramType = paramType.arg(MAV_PARAM_TYPE_UINT32);
break;
case QMetaType::Float:
paramValue = paramValue.arg(j.value().toDouble(), 25, 'g', 12);
paramType = paramType.arg(MAVLINK_TYPE_FLOAT);
paramType = paramType.arg(MAV_PARAM_TYPE_REAL32);
break;
default:
qCritical() << "ABORTED PARAM WRITE TO FILE, NO VALID QVARIANT TYPE" << j.value();
......@@ -789,13 +789,13 @@ void QGCParamWidget::loadParameters()
switch (wpParams.at(3).toUInt())
{
case MAVLINK_TYPE_FLOAT:
case MAV_PARAM_TYPE_REAL32:
changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), wpParams.at(3).toFloat());
break;
case MAVLINK_TYPE_UINT32_T:
case MAV_PARAM_TYPE_UINT32:
changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), wpParams.at(3).toUInt());
break;
case MAVLINK_TYPE_INT32_T:
case MAV_PARAM_TYPE_INT32:
changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), wpParams.at(3).toInt());
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