Commit 871ce028 authored by Gus Grubba's avatar Gus Grubba

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

parents 72f1a42b 4515b8d4
......@@ -35,10 +35,12 @@ QGCView {
property alias advanced: advancedCheckBox.checked
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _vehicleIsRover: _activeVehicle ? _activeVehicle.rover : false
property bool _vehicleArmed: _activeVehicle ? _activeVehicle.armed : false
property bool _vehicleFlying: _activeVehicle ? _activeVehicle.flying : false
property bool _disableDueToArmed: vehicleComponent ? (!vehicleComponent.allowSetupWhileArmed && _vehicleArmed) : false
property bool _disableDueToFlying: vehicleComponent ? (!vehicleComponent.allowSetupWhileFlying && _vehicleFlying) : false
// FIXME: The _vehicleIsRover checkl is a hack to work around https://github.com/PX4/Firmware/issues/10969
property bool _disableDueToFlying: vehicleComponent ? (!_vehicleIsRover && !vehicleComponent.allowSetupWhileFlying && _vehicleFlying) : false
property string _disableReason: _disableDueToArmed ? qsTr("armed") : qsTr("flying")
property real _margins: ScreenTools.defaultFontPixelHeight * 0.5
......
......@@ -188,6 +188,15 @@
<output name="MAIN5">feed-through of RC AUX1 channel</output>
<output name="MAIN6">feed-through of RC AUX2 channel</output>
</airframe>
<airframe id="4041" maintainer="Beat Kueng &lt;beat-kueng@gmx.net&gt;" name="BetaFPV Beta75X 2S Brushless Whoop">
<class>Copter</class>
<maintainer>Beat Kueng &lt;beat-kueng@gmx.net&gt;</maintainer>
<type>Quadrotor H</type>
<output name="MAIN1">motor 1</output>
<output name="MAIN2">motor 2</output>
<output name="MAIN3">motor 3</output>
<output name="MAIN4">motor 4</output>
</airframe>
</airframe_group>
<airframe_group image="QuadRotorWide" name="Quadrotor Wide">
<airframe id="10015" maintainer="Lorenz Meier &lt;lorenz@px4.io&gt;" name="Team Blacksheep Discovery">
......
......@@ -245,7 +245,7 @@ QGCCameraControl::photoStatus()
QString
QGCCameraControl::storageFreeStr()
{
return QGCMapEngine::bigSizeToString(static_cast<quint64>(_storageFree * 1024 * 1024));
return QGCMapEngine::bigSizeToString(static_cast<quint64>(_storageFree) * 1024 * 1024);
}
//-----------------------------------------------------------------------------
......
......@@ -199,7 +199,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
if (!_waitingReadParamIndexMap[componentId].contains(parameterId) &&
!_waitingReadParamNameMap[componentId].contains(parameterName) &&
!_waitingWriteParamNameMap[componentId].contains(parameterName)) {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName;
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Unrequested param update" << parameterName;
}
// Remove this parameter from the waiting lists
......@@ -252,14 +252,14 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
if (totalWaitingParamCount) {
// More params to wait for, restart timer
_waitingParamTimeoutTimer.start();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
} else {
if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
// Still waiting for parameters from default component
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
_waitingParamTimeoutTimer.start();
} else {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
}
}
......@@ -440,7 +440,7 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Request to refresh all parameters for component ID:" << what;
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what;
}
/// Translates FactSystem::defaultComponentId to real component id if needed
......@@ -449,7 +449,7 @@ int ParameterManager::_actualComponentId(int componentId)
if (componentId == FactSystem::defaultComponentId) {
componentId = _vehicle->defaultComponentId();
if (componentId == FactSystem::defaultComponentId) {
qWarning() << _logVehiclePrefix() << "Default component id not set";
qWarning() << _logVehiclePrefix(-1) << "Default component id not set";
}
}
......@@ -564,8 +564,8 @@ bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout)
for(int componentId: _waitingReadParamIndexMap.keys()) {
if (_waitingReadParamIndexMap[componentId].count()) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
}
for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
......@@ -606,7 +606,7 @@ void ParameterManager::_waitingParamTimeout(void)
const int maxBatchSize = 10;
int batchCount = 0;
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout";
// Now that we have timed out for possibly the first time we can activate the index batch queue
_indexBatchQueueActive = true;
......@@ -617,7 +617,7 @@ void ParameterManager::_waitingParamTimeout(void)
if (!paramsRequested && !_waitingForDefaultComponent && !_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
// Initial load is complete but we still don't have any default component params. Wait one more cycle to see if the
// any show up.
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys();
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys();
_waitingParamTimeoutTimer.start();
_waitingForDefaultComponent = true;
return;
......@@ -672,7 +672,7 @@ void ParameterManager::_waitingParamTimeout(void)
Out:
if (paramsRequested) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - re-request";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request";
_waitingParamTimeoutTimer.start();
}
}
......@@ -1121,7 +1121,7 @@ void ParameterManager::_checkInitialLoadComplete(void)
}
_debugCacheCRC.clear();
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Initial load complete";
// Check for index based load failures
QString indexList;
......@@ -1131,7 +1131,7 @@ void ParameterManager::_checkInitialLoadComplete(void)
if (initialLoadFailures) {
indexList += ", ";
}
indexList += QString("%1").arg(paramIndex);
indexList += QString("%1:%2").arg(componentId).arg(paramIndex);
initialLoadFailures = true;
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
}
......@@ -1147,7 +1147,7 @@ void ParameterManager::_checkInitialLoadComplete(void)
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
}
}
......@@ -1161,7 +1161,7 @@ void ParameterManager::_checkInitialLoadComplete(void)
void ParameterManager::_initialRequestTimeout(void)
{
if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retrying initial parameter request list";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Retrying initial parameter request list";
refreshAllParameters();
_initialRequestTimeoutTimer.start();
} else {
......
......@@ -140,7 +140,7 @@ private:
void _addMetaDataToDefaultComponent(void);
QString _remapParamNameToVersion(const QString& paramName);
void _loadOfflineEditingParams(void);
QString _logVehiclePrefix(int componentId = -1);
QString _logVehiclePrefix(int componentId);
void _setLoadProgress(double loadProgress);
bool _fillIndexBatchQueue(bool waitingParamTimeout);
......
......@@ -462,8 +462,8 @@ void APMFirmwarePlugin::_handleIncomingHeartbeat(Vehicle* vehicle, mavlink_messa
bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
//-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues
if (message->compid == MAV_COMP_ID_UDP_BRIDGE) {
// Only translate messages which come from the autopilot. All other components are expected to follow current mavlink spec.
if (message->compid != MAV_COMP_ID_AUTOPILOT1) {
return true;
}
......
......@@ -3645,6 +3645,11 @@ Used to calculate increased terrain random walk nosie due to movement</short_des
<long_desc>The mavlink hearbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.</long_desc>
<boolean />
</parameter>
<parameter default="0" name="MAV_ODOM_LP" type="INT32">
<short_desc>Activate ODOMETRY loopback</short_desc>
<long_desc>If set, it gets the data from 'vehicle_visual_odometry' instead of 'vehicle_odometry' serving as a loopback of the received ODOMETRY messages on the Mavlink receiver.</long_desc>
<boolean />
</parameter>
<parameter default="0" name="MAV_PROTO_VER" type="INT32">
<short_desc>MAVLink protocol version</short_desc>
<values>
......@@ -4151,8 +4156,12 @@ default 1.5 turns per second</short_desc>
</parameter>
<parameter default="0" name="MC_AIRMODE" type="INT32">
<short_desc>Multicopter air-mode</short_desc>
<long_desc>The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable.</long_desc>
<boolean />
<long_desc>The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch.</long_desc>
<values>
<value code="0">Disabled</value>
<value code="1">Roll/Pitch</value>
<value code="2">Roll/Pitch/Yaw</value>
</values>
</parameter>
<parameter default="0" name="MC_BAT_SCALE_EN" type="INT32">
<short_desc>Battery power level scaler</short_desc>
......
......@@ -89,6 +89,7 @@
#include "FactValueSliderListModel.h"
#include "ShapeFileHelper.h"
#include "QGCFileDownload.h"
#include "FirmwareImage.h"
#ifndef NO_SERIAL_LINK
#include "SerialLink.h"
......@@ -236,11 +237,13 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
// Parse command line options
bool fClearSettingsOptions = false; // Clear stored settings
bool fClearCache = false; // Clear parameter/airframe caches
bool logging = false; // Turn on logging
QString loggingOptions;
CmdLineOpt_t rgCmdLineOptions[] = {
{ "--clear-settings", &fClearSettingsOptions, nullptr },
{ "--clear-cache", &fClearCache, nullptr },
{ "--logging", &logging, &loggingOptions },
{ "--fake-mobile", &_fakeMobile, nullptr },
{ "--log-output", &_logOutput, nullptr },
......@@ -309,6 +312,15 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
}
settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION);
if (fClearCache) {
QDir dir(ParameterManager::parameterCacheDir());
dir.removeRecursively();
QFile airframe(cachedAirframeMetaDataFile());
airframe.remove();
QFile parameter(cachedParameterMetaDataFile());
parameter.remove();
}
// Set up our logging filters
QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(loggingOptions);
......@@ -839,3 +851,16 @@ void QGCApplication::_gpsNumSatellites(int numSatellites)
_gpsRtkFactGroup->numSatellites()->setRawValue(numSatellites);
}
QString QGCApplication::cachedParameterMetaDataFile(void)
{
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
return parameterDir.filePath(QStringLiteral("ParameterFactMetaData.xml"));
}
QString QGCApplication::cachedAirframeMetaDataFile(void)
{
QSettings settings;
QDir airframeDir = QFileInfo(settings.fileName()).dir();
return airframeDir.filePath(QStringLiteral("PX4AirframeFactMetaData.xml"));
}
......@@ -98,6 +98,9 @@ public:
FactGroup* gpsRtkFactGroup(void) { return _gpsRtkFactGroup; }
static QString cachedParameterMetaDataFile(void);
static QString cachedAirframeMetaDataFile(void);
public slots:
/// You can connect to this slot to show an information message box from a different thread.
void informationMessageBoxOnMainThread(const QString& title, const QString& msg);
......
......@@ -275,12 +275,8 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
_jsonParamXmlKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes
if (success) {
// Use settings location as our work directory, this way is something goes wrong the file is still there
// sitting next to the cache files.
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
QString parameterFilename = parameterDir.filePath("ParameterFactMetaData.xml");
QFile parameterFile(parameterFilename);
QString parameterFilename = QGCApplication::cachedParameterMetaDataFile();
QFile parameterFile(QGCApplication::cachedParameterMetaDataFile());
if (parameterFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
qint64 bytesWritten = parameterFile.write(decompressedBytes);
......@@ -306,12 +302,9 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
_jsonAirframeXmlKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes
if (success) {
// We cache the airframe xml in the same location as settings and parameters
QSettings settings;
QDir airframeDir = QFileInfo(settings.fileName()).dir();
QString airframeFilename = airframeDir.filePath("PX4AirframeFactMetaData.xml");
QString airframeFilename = QGCApplication::cachedAirframeMetaDataFile();
//qDebug() << airframeFilename;
QFile airframeFile(airframeFilename);
QFile airframeFile(QGCApplication::cachedAirframeMetaDataFile());
if (airframeFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
qint64 bytesWritten = airframeFile.write(decompressedBytes);
......
......@@ -34,7 +34,7 @@ QGCView {
"So make sure to test your changes thoroughly before using them in flight.</p>" +
"<p>Click 'Load Custom Qml file' to provide your custom qml file.</p>" +
"<p>Click 'Reset' to reset to none.</p>" +
"<p>Example usage: <a href='https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html'>https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html</a></p>"
"<p>Example usage: <a href='https://docs.qgroundcontrol.com/en/app_menu/custom_command_widget.html'>https://docs.qgroundcontrol.com/en/app_menu/custom_command_widget.html</a></p>"
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......
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