Browse Source

Merge branch 'v10release' of github.com:pixhawk/qgroundcontrol into v10release

QGC4.4
LM 14 years ago
parent
commit
a128df009b
  1. 2
      src/configuration.h
  2. 36
      src/libs/opmapcontrol/src/core/pureimagecache.cpp
  3. 1
      src/uas/UASManager.h
  4. 8
      src/ui/MAVLinkDecoder.cc
  5. 4
      src/ui/QGCMAVLinkInspector.cc

2
src/configuration.h

@ -12,7 +12,7 @@ @@ -12,7 +12,7 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.0.0 (Alpha RC3)"
#define QGC_APPLICATION_VERSION "v. 1.0.0 (Alpha RC16)"
namespace QGC

36
src/libs/opmapcontrol/src/core/pureimagecache.cpp

@ -226,31 +226,25 @@ namespace core { @@ -226,31 +226,25 @@ namespace core {
qDebug()<<"Cache dir="<<dir<<" Try to GET:"<<pos.X()+","+pos.Y();
#endif //DEBUG_PUREIMAGECACHE
{
QString db=dir+"Data.qmdb";
{
QSqlDatabase cn;
QSqlDatabase cn;
cn = QSqlDatabase::addDatabase("QSQLITE",QString::number(id));
cn = QSqlDatabase::addDatabase("QSQLITE",QString::number(id));
cn.setDatabaseName(db);
cn.setConnectOptions("QSQLITE_ENABLE_SHARED_CACHE");
if(cn.open())
{
{
QSqlQuery query(cn);
query.exec(QString("SELECT Tile FROM TilesData WHERE id = (SELECT id FROM Tiles WHERE X=%1 AND Y=%2 AND Zoom=%3 AND Type=%4)").arg(pos.X()).arg(pos.Y()).arg(zoom).arg((int) type));
query.next();
if(query.isValid())
{
ar=query.value(0).toByteArray();
}
}
cn.close();
cn.setDatabaseName(db);
cn.setConnectOptions("QSQLITE_ENABLE_SHARED_CACHE");
if(cn.open())
{
QSqlQuery query(cn);
query.exec(QString("SELECT Tile FROM TilesData WHERE id = (SELECT id FROM Tiles WHERE X=%1 AND Y=%2 AND Zoom=%3 AND Type=%4)").arg(pos.X()).arg(pos.Y()).arg(zoom).arg((int) type));
query.next();
if(query.isValid())
{
ar=query.value(0).toByteArray();
}
}
}
QSqlDatabase::removeDatabase(QString::number(id));
cn.close();
}
QSqlDatabase::removeDatabase(QString::number(id));
lock.unlock();
return ar;
}

1
src/uas/UASManager.h

@ -246,6 +246,7 @@ protected: @@ -246,6 +246,7 @@ protected:
void initReference(const double & latitude, const double & longitude, const double & altitude);
signals:
void UASCreated(UASInterface* UAS);
/** @brief The UAS currently under main operator control changed */
void activeUASSet(UASInterface* UAS);

8
src/ui/MAVLinkDecoder.cc

@ -247,7 +247,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 @@ -247,7 +247,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
fieldType = QString("uint64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (quint64) nums[j], time);
}
}
else
@ -255,7 +255,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 @@ -255,7 +255,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// Single value
uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
fieldType = "uint64_t";
emit valueChanged(msg->sysid, name, fieldType, n, time);
emit valueChanged(msg->sysid, name, fieldType, (quint64) n, time);
}
break;
case MAVLINK_TYPE_INT64_T:
@ -265,7 +265,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 @@ -265,7 +265,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
fieldType = QString("int64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (qint64) nums[j], time);
}
}
else
@ -273,7 +273,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 @@ -273,7 +273,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// Single value
int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
fieldType = "int64_t";
emit valueChanged(msg->sysid, name, fieldType, n, time);
emit valueChanged(msg->sysid, name, fieldType, (qint64) n, time);
}
break;
}

4
src/ui/QGCMAVLinkInspector.cc

@ -298,7 +298,7 @@ void QGCMAVLinkInspector::updateField(int msgid, int fieldid, QTreeWidgetItem* i @@ -298,7 +298,7 @@ void QGCMAVLinkInspector::updateField(int msgid, int fieldid, QTreeWidgetItem* i
// Single value
uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "uint64_t");
item->setData(1, Qt::DisplayRole, n);
item->setData(1, Qt::DisplayRole, (quint64) n);
}
break;
case MAVLINK_TYPE_INT64_T:
@ -320,7 +320,7 @@ void QGCMAVLinkInspector::updateField(int msgid, int fieldid, QTreeWidgetItem* i @@ -320,7 +320,7 @@ void QGCMAVLinkInspector::updateField(int msgid, int fieldid, QTreeWidgetItem* i
// Single value
int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "int64_t");
item->setData(1, Qt::DisplayRole, n);
item->setData(1, Qt::DisplayRole, (qint64) n);
}
break;
}

Loading…
Cancel
Save