diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 8f8e8eebbe224ac952ad8bd2dbf4eca70e2495a5..95763993410281d07e3f3eb6597cc5617c50bbfc 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -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; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 37b8ad3c5218e086e1204650b753e594eb2189d0..a68c0eb75223158e364e61fcfc9ac0b8cd949344 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -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)); } }