Browse Source

Added PNGs for mac icon, moved UAS timestamps to microseconds instead of milliseconds

QGC4.4
lm 15 years ago
parent
commit
cd6cb91512
  1. BIN
      images/icons/macx_128x128x32.png
  2. BIN
      images/icons/macx_16x16x1.png
  3. BIN
      images/icons/macx_16x16x32.png
  4. BIN
      images/icons/macx_32x32x1.png
  5. BIN
      images/icons/macx_32x32x32.png
  6. BIN
      images/icons/macx_48x48x1.png
  7. BIN
      images/icons/macx_48x48x32.png
  8. 15
      src/comm/MAVLinkProtocol.cc
  9. 2
      src/comm/MAVLinkProtocol.h
  10. 10
      src/uas/UAS.cc
  11. 2
      src/ui/uas/UASInfoWidget.cc

BIN
images/icons/macx_128x128x32.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

BIN
images/icons/macx_16x16x1.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 121 B

BIN
images/icons/macx_16x16x32.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 761 B

BIN
images/icons/macx_32x32x1.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 179 B

BIN
images/icons/macx_32x32x32.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.3 KiB

BIN
images/icons/macx_48x48x1.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 255 B

BIN
images/icons/macx_48x48x32.png

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.6 KiB

15
src/comm/MAVLinkProtocol.cc

@ -61,6 +61,8 @@ MAVLinkProtocol::MAVLinkProtocol() : @@ -61,6 +61,8 @@ MAVLinkProtocol::MAVLinkProtocol() :
heartbeatTimer->start(1000/heartbeatRate);
totalReceiveCounter = 0;
totalLossCounter = 0;
currReceiveCounter = 0;
currLossCounter = 0;
for (int i = 0; i < 256; i++)
{
for (int j = 0; j < 256; j++)
@ -131,6 +133,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link) @@ -131,6 +133,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
}
// Increase receive counter
totalReceiveCounter++;
currReceiveCounter++;
qint64 lastLoss = totalLossCounter;
// Update last packet index
if (lastIndex[message.sysid][message.compid] == -1)
@ -150,7 +153,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link) @@ -150,7 +153,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
int safeguard = 0;
//qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
while(lastIndex[message.sysid][message.compid] != message.seq && safeguard < 1)
while(lastIndex[message.sysid][message.compid] != message.seq && safeguard < 255)
{
if (lastIndex[message.sysid][message.compid] == 255)
{
@ -161,6 +164,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link) @@ -161,6 +164,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
lastIndex[message.sysid][message.compid]++;
}
totalLossCounter++;
currLossCounter++;
safeguard++;
}
}
@ -171,12 +175,17 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link) @@ -171,12 +175,17 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
// while (lastCompIndex->value(message.compid, 0)+1 )
// }
//if ()
if (lastLoss != totalLossCounter || (totalReceiveCounter / 64) == 0)
// If a new loss was detected or we just hit one 128th packet step
if (lastLoss != totalLossCounter || (totalReceiveCounter & 0b1111111) == 0)
{
// Calculate new loss ratio
// Receive loss
float receiveLoss = (double)totalLossCounter/(double)(totalReceiveCounter+totalLossCounter);
float receiveLoss = (double)currLossCounter/(double)(currReceiveCounter+currLossCounter);
receiveLoss *= 100.0f;
// qDebug() << "LOSSCHANGED" << receiveLoss;
currLossCounter = 0;
currReceiveCounter = 0;
emit receiveLossChanged(receiveLoss);
}

2
src/comm/MAVLinkProtocol.h

@ -90,6 +90,8 @@ protected: @@ -90,6 +90,8 @@ protected:
int lastIndex[256][256];
int totalReceiveCounter;
int totalLossCounter;
int currReceiveCounter;
int currLossCounter;
signals:
/** @brief Message received and directly copied via signal */

10
src/uas/UAS.cc

@ -225,15 +225,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -225,15 +225,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_aux_status_t status;
mavlink_msg_aux_status_decode(&message, &status);
emit loadChanged(this, status.load/100.0f);
emit valueChanged(this, "Load", status.load/1000.0f, MG::TIME::getGroundTimeNow());
emit loadChanged(this, status.load/10.0f);
emit valueChanged(this, "Load", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
}
break;
case MAVLINK_MSG_ID_RAW_IMU:
{
mavlink_raw_imu_t raw;
mavlink_msg_raw_imu_decode(&message, &raw);
quint64 time = raw.msec;
quint64 time = raw.msec/1000;
if (time == 0)
{
time = MG::TIME::getGroundTimeNow();
@ -285,7 +285,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -285,7 +285,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = mavlink_msg_attitude_get_msec(&message);
quint64 time = mavlink_msg_attitude_get_msec(&message)/1000;
if (time == 0)
{
time = MG::TIME::getGroundTimeNow();
@ -316,7 +316,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -316,7 +316,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_position_t pos;
mavlink_msg_position_decode(&message, &pos);
quint64 time = pos.msec;
quint64 time = pos.msec/1000;
if (time == 0)
{
time = MG::TIME::getGroundTimeNow();

2
src/ui/uas/UASInfoWidget.cc

@ -113,7 +113,7 @@ void UASInfoWidget::updateCPULoad(UASInterface* uas, double load) @@ -113,7 +113,7 @@ void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
{
if (activeUAS == uas)
{
this->load = load*100.0f;
this->load = load;
}
}

Loading…
Cancel
Save