Browse Source

Merge branch 'master' of github.com:mavlink/qgroundcontrol

QGC4.4
Lorenz Meier 13 years ago
parent
commit
127eb2ce54
  1. 9
      deploy/mac_create_dmg.sh
  2. 2
      libs/lib/mac64/include/osgDB/Serializer
  3. 8
      libs/opmapcontrol/src/core/cache.cpp
  4. 4
      src/comm/MAVLinkProtocol.cc
  5. 2
      src/ui/HUD.cc
  6. 20
      src/ui/MainWindow.cc
  7. 8
      src/ui/QGCVehicleConfig.cc
  8. 2
      src/ui/map3D/Imagery.cc

9
deploy/mac_create_dmg.sh

@ -1,12 +1,15 @@
#!/bin/sh #!/bin/sh
cp -r ../../qgroundcontrol-build-desktop/qgroundcontrol.app . cp -r ../../qgroundcontrol-build-desktop-Desktop_Qt_4_8_1_for_GCC__Qt_SDK__Release/qgroundcontrol.app .
cp -r ../audio qgroundcontrol.app/Contents/MacOs/. cp -r ../files/audio qgroundcontrol.app/Contents/MacOs/.
mkdir -p qgroundcontrol.app/Contents/Frameworks/ mkdir -p qgroundcontrol.app/Contents/Frameworks/
mkdir -p qgroundcontrol.app/Contents/PlugIns/imageformats
mkdir -p qgroundcontrol.app/Contents/PlugIns/codecs
mkdir -p qgroundcontrol.app/Contents/PlugIns/accessible
# SDL is not copied by Qt - for whatever reason # SDL is not copied by Qt - for whatever reason
cp -r /Library/Frameworks/SDL.framework qgroundcontrol.app/Contents/Frameworks/. cp -r /Library/Frameworks/SDL.framework qgroundcontrol.app/Contents/Frameworks/.
echo -e '\n\nStarting to create disk image. This may take a while..\n' echo -e '\n\nStarting to create disk image. This may take a while..\n'
macdeployqt qgroundcontrol.app -dmg $HOME/QtSDK/Desktop/Qt/4.8.1/gcc/bin/macdeployqt qgroundcontrol.app -dmg
rm -rf qgroundcontrol.app rm -rf qgroundcontrol.app
echo -e '\n\n QGroundControl .DMG file is now ready for publishing\n' echo -e '\n\n QGroundControl .DMG file is now ready for publishing\n'

2
libs/lib/mac64/include/osgDB/Serializer

@ -47,7 +47,7 @@ public:
if ( _valueToString.find(value)!=_valueToString.end() ) if ( _valueToString.find(value)!=_valueToString.end() )
{ {
osg::notify(osg::WARN) << "Duplicate enum value " << value osg::notify(osg::WARN) << "Duplicate enum value " << value
<< " with old string: " << _valueToString[value] << " with old string: " << _valueToString[value].c_str()
<< " and new string: " << str << std::endl; << " and new string: " << str << std::endl;
} }
_valueToString[value] = str; _valueToString[value] = str;

8
libs/opmapcontrol/src/core/cache.cpp

@ -41,9 +41,9 @@ namespace core {
void Cache::setCacheLocation(const QString& value) void Cache::setCacheLocation(const QString& value)
{ {
cache=value; cache=value;
routeCache = cache + "RouteCache" + QDir::separator(); routeCache = cache + "RouteCache/";
geoCache = cache + "GeocoderCache"+ QDir::separator(); geoCache = cache + "GeocoderCache/";
placemarkCache = cache + "PlacemarkCache" + QDir::separator(); placemarkCache = cache + "PlacemarkCache/";
ImageCache.setGtileCache(value); ImageCache.setGtileCache(value);
} }
QString Cache::CacheLocation() QString Cache::CacheLocation()
@ -54,7 +54,7 @@ namespace core {
{ {
if(cache.isNull()|cache.isEmpty()) if(cache.isNull()|cache.isEmpty())
{ {
cache= Utils::PathUtils().GetStoragePath()+"mapscache"+QDir::separator(); cache = QDir::homePath() + "/mapscache/";
setCacheLocation(cache); setCacheLocation(cache);
} }
} }

4
src/comm/MAVLinkProtocol.cc

@ -539,8 +539,8 @@ void MAVLinkProtocol::sendHeartbeat()
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_auth_key_t auth; mavlink_auth_key_t auth;
if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN); memset(&auth, 0, sizeof(auth));
strcpy(auth.key, m_authKey.toStdString().c_str()); memcpy(auth.key, m_authKey.toStdString().c_str(), qMin(m_authKey.length(), MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN));
mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth); mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
sendMessage(msg); sendMessage(msg);
} }

2
src/ui/HUD.cc

@ -797,7 +797,7 @@ void HUD::paintHUD()
// const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f)+180.f; // const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f)+180.f;
// YAW is in compass-human readable format, so 0 .. 360 deg. // YAW is in compass-human readable format, so 0 .. 360 deg.
float yawDeg = ((yawLP/M_PI)*180.0f)+180.0f; float yawDeg = (yawLP / M_PI) * 180.0f;
if (yawDeg < 0) yawDeg += 360; if (yawDeg < 0) yawDeg += 360;
if (yawDeg > 360) yawDeg -= 360; if (yawDeg > 360) yawDeg -= 360;
/* final safeguard for really stupid systems */ /* final safeguard for really stupid systems */

20
src/ui/MainWindow.cc

@ -552,11 +552,11 @@ void MainWindow::buildCommonWidgets()
addCentralWidget(protocolWidget, "Mavlink Generator"); addCentralWidget(protocolWidget, "Mavlink Generator");
} }
if (!firmwareUpdateWidget) // if (!firmwareUpdateWidget)
{ // {
firmwareUpdateWidget = new QGCFirmwareUpdate(this); // firmwareUpdateWidget = new QGCFirmwareUpdate(this);
addCentralWidget(firmwareUpdateWidget, "Firmware Update"); // addCentralWidget(firmwareUpdateWidget, "Firmware Update");
} // }
if (!hudWidget) if (!hudWidget)
{ {
@ -564,11 +564,11 @@ void MainWindow::buildCommonWidgets()
addCentralWidget(hudWidget, tr("Head Up Display")); addCentralWidget(hudWidget, tr("Head Up Display"));
} }
if (!configWidget) // if (!configWidget)
{ // {
configWidget = new QGCVehicleConfig(this); // configWidget = new QGCVehicleConfig(this);
addCentralWidget(configWidget, tr("Vehicle Configuration")); // addCentralWidget(configWidget, tr("Vehicle Configuration"));
} // }
if (!dataplotWidget) if (!dataplotWidget)
{ {

8
src/ui/QGCVehicleConfig.cc

@ -146,13 +146,13 @@ void QGCVehicleConfig::requestCalibrationRC()
for (unsigned int i = 0; i < chanMax; ++i) for (unsigned int i = 0; i < chanMax; ++i)
{ {
mav->requestParameter(0, minTpl.arg(i)); mav->requestParameter(0, minTpl.arg(i));
usleep(5000); QGC::SLEEP::usleep(5000);
mav->requestParameter(0, trimTpl.arg(i)); mav->requestParameter(0, trimTpl.arg(i));
usleep(5000); QGC::SLEEP::usleep(5000);
mav->requestParameter(0, maxTpl.arg(i)); mav->requestParameter(0, maxTpl.arg(i));
usleep(5000); QGC::SLEEP::usleep(5000);
mav->requestParameter(0, revTpl.arg(i)); mav->requestParameter(0, revTpl.arg(i));
usleep(5000); QGC::SLEEP::usleep(5000);
} }
} }

2
src/ui/map3D/Imagery.cc

@ -614,7 +614,7 @@ Imagery::getTileLocation(int tileX, int tileY, int zoomLevel,
<< "&y=" << tileY << "&z=" << zoomLevel; << "&y=" << tileY << "&z=" << zoomLevel;
break; break;
case OFFLINE_SATELLITE: case OFFLINE_SATELLITE:
oss << mImageryPath << "/200/color/" << tileY oss << mImageryPath.c_str() << "/200/color/" << tileY
<< "/tile-"; << "/tile-";
if (tileResolution < 1.0) if (tileResolution < 1.0)
{ {

Loading…
Cancel
Save