Commit e18b11cd authored by Andrew Tridgell's avatar Andrew Tridgell

fixed build

name element of mavlink_named_value is uint8_t
parent 3466d9f2
......@@ -167,7 +167,7 @@ void MAVLinkSimulationMAV::mainloop()
// Name of the value, maximum 10 characters
// see full message specs at:
// http://pixhawk.ethz.ch/wiki/mavlink/
strcpy(val.name, "FLOAT");
strcpy((char *)val.name, "FLOAT");
// Value, in this case 0.5
val.value = 0.5f;
......@@ -195,7 +195,7 @@ void MAVLinkSimulationMAV::mainloop()
// Name of the value, maximum 10 characters
// see full message specs at:
// http://pixhawk.ethz.ch/wiki/mavlink/
strcpy(valint.name, "INTEGER");
strcpy((char *)valint.name, "INTEGER");
// Value, in this case 18000
valint.value = 18000;
......
......@@ -170,13 +170,13 @@ void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
mavlink_named_value_float_t val;
mavlink_msg_named_value_float_decode(&message, &val);
emit valueChanged(this->getUASID(), QString(val.name), tr("raw"), val.value, getUnixTime(0));
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime(0));
}
else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
{
mavlink_named_value_int_t val;
mavlink_msg_named_value_int_decode(&message, &val);
emit valueChanged(this->getUASID(), QString(val.name), tr("raw"), (float)val.value, getUnixTime(0));
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), (float)val.value, getUnixTime(0));
}
}
......
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