Commit 68e7c1c0 authored by LM's avatar LM

Fixed accidentally commited hacks

parent 0c80a85c
......@@ -499,7 +499,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
if (message.compid == 201) emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
if (!wrongComponent)
{
......@@ -577,7 +577,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
quint64 time = getUnixTime(pos.time_boot_ms);
// Emit position always with component ID
if (message.compid == 201) emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
if (!wrongComponent)
......
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