Commit ec091ecc authored by Don Gagne's avatar Don Gagne

Changed default component id discovery

Use component id from heartbeat
parent 1a2ce057
...@@ -52,7 +52,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle) ...@@ -52,7 +52,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
, _initialLoadComplete(false) , _initialLoadComplete(false)
, _waitingForDefaultComponent(false) , _waitingForDefaultComponent(false)
, _saveRequired(false) , _saveRequired(false)
, _defaultComponentId(MAV_COMP_ID_ALL)
, _parameterSetMajorVersion(-1) , _parameterSetMajorVersion(-1)
, _parameterMetaData(NULL) , _parameterMetaData(NULL)
, _prevWaitingReadParamIndexCount(0) , _prevWaitingReadParamIndexCount(0)
...@@ -81,9 +80,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle) ...@@ -81,9 +80,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterManager::_parameterUpdate); connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterManager::_parameterUpdate);
_defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Default component param" << _defaultComponentIdParam;
// Ensure the cache directory exists // Ensure the cache directory exists
QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache"); QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
refreshAllParameters(); refreshAllParameters();
...@@ -163,12 +159,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -163,12 +159,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Seeing component for first time - paramcount:" << parameterCount; qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Seeing component for first time - paramcount:" << parameterCount;
} }
// Determine default component id
if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Default component id determined";
_defaultComponentId = componentId;
}
bool componentParamsComplete = false; bool componentParamsComplete = false;
if (_waitingReadParamIndexMap[componentId].count() == 1) { if (_waitingReadParamIndexMap[componentId].count() == 1) {
// We need to know when we get the last param from a component in order to complete setup // We need to know when we get the last param from a component in order to complete setup
...@@ -229,13 +219,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -229,13 +219,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_waitingParamTimeoutTimer.start(); _waitingParamTimeoutTimer.start();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount; qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
} else { } else {
if (_defaultComponentId == MAV_COMP_ID_ALL && !_defaultComponentIdParam.isEmpty()) { qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
// Still waiting for default component id, restart timer
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer (still waiting for default component)";
_waitingParamTimeoutTimer.start();
} else {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
}
} }
// Update progress bar for waiting reads // Update progress bar for waiting reads
...@@ -306,7 +290,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -306,7 +290,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
fact->_containerSetRawValue(value); fact->_containerSetRawValue(value);
if (componentParamsComplete) { if (componentParamsComplete) {
if (componentId == _defaultComponentId) { if (componentId == _vehicle->defaultComponentId()) {
// Add meta data to default component. We need to do this before we setup the group map since group // Add meta data to default component. We need to do this before we setup the group map since group
// map requires meta data. // map requires meta data.
_addMetaDataToDefaultComponent(); _addMetaDataToDefaultComponent();
...@@ -337,8 +321,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -337,8 +321,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_prevWaitingReadParamNameCount = waitingReadParamNameCount; _prevWaitingReadParamNameCount = waitingReadParamNameCount;
_prevWaitingWriteParamNameCount = waitingWriteParamNameCount; _prevWaitingWriteParamNameCount = waitingWriteParamNameCount;
// Don't fail initial load complete if default component isn't found yet. That will be handled in wait timeout check. _checkInitialLoadComplete();
_checkInitialLoadComplete(false /* failIfNoDefaultComponent */);
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete"; qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
} }
...@@ -409,33 +392,11 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) ...@@ -409,33 +392,11 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Request to refresh all parameters for component ID:" << what; qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Request to refresh all parameters for component ID:" << what;
} }
void ParameterManager::_determineDefaultComponentId(void)
{
if (_defaultComponentId == MAV_COMP_ID_ALL) {
// We don't have a default component id yet. That means the plugin can't provide
// the param to trigger off of. Instead we use the most prominent component id in
// the set of parameters. Better than nothing!
int largestCompParamCount = 0;
foreach(int componentId, _mapParameterName2Variant.keys()) {
int compParamCount = _mapParameterName2Variant[componentId].count();
if (compParamCount > largestCompParamCount) {
largestCompParamCount = compParamCount;
_defaultComponentId = componentId;
}
}
if (_defaultComponentId == MAV_COMP_ID_ALL) {
qWarning() << _logVehiclePrefix() << "All parameters missing, unable to determine default component id";
}
}
}
/// Translates FactSystem::defaultComponentId to real component id if needed /// Translates FactSystem::defaultComponentId to real component id if needed
int ParameterManager::_actualComponentId(int componentId) int ParameterManager::_actualComponentId(int componentId)
{ {
if (componentId == FactSystem::defaultComponentId) { if (componentId == FactSystem::defaultComponentId) {
componentId = _defaultComponentId; componentId = _vehicle->defaultComponentId();
if (componentId == FactSystem::defaultComponentId) { if (componentId == FactSystem::defaultComponentId) {
qWarning() << _logVehiclePrefix() << "Default component id not set"; qWarning() << _logVehiclePrefix() << "Default component id not set";
} }
...@@ -569,18 +530,17 @@ void ParameterManager::_waitingParamTimeout(void) ...@@ -569,18 +530,17 @@ void ParameterManager::_waitingParamTimeout(void)
} }
} }
if (!paramsRequested && _defaultComponentId == MAV_COMP_ID_ALL && !_defaultComponentIdParam.isEmpty() && !_waitingForDefaultComponent) { if (!paramsRequested && !_waitingForDefaultComponent && !_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
// Initial load is complete but we still don't have default component params. Wait one more cycle to see if the // Initial load is complete but we still don't have any default component params. Wait one more cycle to see if the
// default component finally shows up. // any show up.
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component id"; qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component params";
_waitingParamTimeoutTimer.start(); _waitingParamTimeoutTimer.start();
_waitingForDefaultComponent = true; _waitingForDefaultComponent = true;
return; return;
} }
_waitingForDefaultComponent = false; _waitingForDefaultComponent = false;
// Check for initial load complete success/failure. Fail load if we don't have a default component at this point. _checkInitialLoadComplete();
_checkInitialLoadComplete(true /* failIfNoDefaultComponent */);
if (!paramsRequested) { if (!paramsRequested) {
foreach(int componentId, _waitingWriteParamNameMap.keys()) { foreach(int componentId, _waitingWriteParamNameMap.keys()) {
...@@ -955,11 +915,6 @@ FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE ma ...@@ -955,11 +915,6 @@ FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE ma
void ParameterManager::_addMetaDataToDefaultComponent(void) void ParameterManager::_addMetaDataToDefaultComponent(void)
{ {
if (_defaultComponentId == MAV_COMP_ID_ALL) {
// We don't know what the default component is so we can't support meta data
return;
}
if (_parameterMetaData) { if (_parameterMetaData) {
return; return;
} }
...@@ -974,14 +929,13 @@ void ParameterManager::_addMetaDataToDefaultComponent(void) ...@@ -974,14 +929,13 @@ void ParameterManager::_addMetaDataToDefaultComponent(void)
_parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile); _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
// Loop over all parameters in default component adding meta data // Loop over all parameters in default component adding meta data
QVariantMap& factMap = _mapParameterName2Variant[_defaultComponentId]; QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()];
foreach (const QString& key, factMap.keys()) { foreach (const QString& key, factMap.keys()) {
_vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value<Fact*>(), _vehicle->vehicleType()); _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value<Fact*>(), _vehicle->vehicleType());
} }
} }
/// @param failIfNoDefaultComponent true: Fails parameter load if no default component but we should have one void ParameterManager::_checkInitialLoadComplete(void)
void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
{ {
// Already processed? // Already processed?
if (_initialLoadComplete) { if (_initialLoadComplete) {
...@@ -995,11 +949,6 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent) ...@@ -995,11 +949,6 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
} }
} }
if (!failIfNoDefaultComponent && _defaultComponentId == MAV_COMP_ID_ALL && !_defaultComponentIdParam.isEmpty()) {
// We are still waiting for default component to show up
return;
}
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete // We aren't waiting for any more initial parameter updates, initial parameter loading is complete
_initialLoadComplete = true; _initialLoadComplete = true;
...@@ -1031,23 +980,10 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent) ...@@ -1031,23 +980,10 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
if (!qgcApp()->runningUnitTests()) { if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList; qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
} }
} else if (_defaultComponentId == MAV_COMP_ID_ALL && !_defaultComponentIdParam.isEmpty()) {
// Missing default component when we should have one
_missingParameters = true;
QString errorMsg = tr("QGroundControl did not receive parameters from the default component for vehicle %1. "
"This will cause QGroundControl to be unable to display its full user interface. "
"If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.").arg(_vehicle->id());
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "Default component was never found, param:" << _defaultComponentIdParam;
}
} }
// Signal load complete // Signal load complete
_parametersReady = true; _parametersReady = true;
_determineDefaultComponentId();
_vehicle->autopilotPlugin()->parametersReadyPreChecks(); _vehicle->autopilotPlugin()->parametersReadyPreChecks();
emit parametersReadyChanged(true); emit parametersReadyChanged(true);
emit missingParametersChanged(_missingParameters); emit missingParametersChanged(_missingParameters);
...@@ -1056,12 +992,11 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent) ...@@ -1056,12 +992,11 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
void ParameterManager::_initialRequestTimeout(void) void ParameterManager::_initialRequestTimeout(void)
{ {
if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) { if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retyring initial parameter request list"; qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retrying initial parameter request list";
refreshAllParameters(); refreshAllParameters();
_initialRequestTimeoutTimer.start(); _initialRequestTimeoutTimer.start();
} else { } else {
if (!_vehicle->genericFirmware()) { if (!_vehicle->genericFirmware()) {
// Generic vehicles (like BeBop) may not have any parameters, so don't annoy the user
QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. " QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
"This will cause QGroundControl to be unable to display its full user interface.").arg(_vehicle->id()); "This will cause QGroundControl to be unable to display its full user interface.").arg(_vehicle->id());
qCDebug(ParameterManagerLog) << errorMsg; qCDebug(ParameterManagerLog) << errorMsg;
...@@ -1282,7 +1217,8 @@ void ParameterManager::_loadOfflineEditingParams(void) ...@@ -1282,7 +1217,8 @@ void ParameterManager::_loadOfflineEditingParams(void)
QStringList paramData = line.split("\t"); QStringList paramData = line.split("\t");
Q_ASSERT(paramData.count() == 5); Q_ASSERT(paramData.count() == 5);
_defaultComponentId = paramData.at(1).toInt(); int defaultComponentId = paramData.at(1).toInt();
_vehicle->setOfflineEditingDefaultComponentId(defaultComponentId);
QString paramName = paramData.at(2); QString paramName = paramData.at(2);
QString valStr = paramData.at(3); QString valStr = paramData.at(3);
MAV_PARAM_TYPE paramType = static_cast<MAV_PARAM_TYPE>(paramData.at(4).toUInt()); MAV_PARAM_TYPE paramType = static_cast<MAV_PARAM_TYPE>(paramData.at(4).toUInt());
...@@ -1321,8 +1257,8 @@ void ParameterManager::_loadOfflineEditingParams(void) ...@@ -1321,8 +1257,8 @@ void ParameterManager::_loadOfflineEditingParams(void)
_parameterSetMajorVersion = paramValue.toInt(); _parameterSetMajorVersion = paramValue.toInt();
} }
Fact* fact = new Fact(_defaultComponentId, paramName, _mavTypeToFactType(paramType), this); Fact* fact = new Fact(defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
_mapParameterName2Variant[_defaultComponentId][paramName] = QVariant::fromValue(fact); _mapParameterName2Variant[defaultComponentId][paramName] = QVariant::fromValue(fact);
} }
_addMetaDataToDefaultComponent(); _addMetaDataToDefaultComponent();
......
...@@ -104,8 +104,6 @@ public: ...@@ -104,8 +104,6 @@ public:
/// If this file is newer than anything in the cache, cache it as the latest version /// If this file is newer than anything in the cache, cache it as the latest version
static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType); static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType);
int defaultComponentId(void) { return _defaultComponentId; }
/// Saves the specified param set to the json object. /// Saves the specified param set to the json object.
/// @param componentId Component id which contains params, MAV_COMP_ID_ALL to save all components /// @param componentId Component id which contains params, MAV_COMP_ID_ALL to save all components
/// @param paramsToSave List of params names to save, empty to save all for component /// @param paramsToSave List of params names to save, empty to save all for component
...@@ -139,7 +137,6 @@ protected: ...@@ -139,7 +137,6 @@ protected:
private: private:
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
int _actualComponentId(int componentId); int _actualComponentId(int componentId);
void _determineDefaultComponentId(void);
void _setupGroupMap(void); void _setupGroupMap(void);
void _readParameterRaw(int componentId, const QString& paramName, int paramIndex); void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
...@@ -154,7 +151,7 @@ private: ...@@ -154,7 +151,7 @@ private:
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType); MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType); FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
void _saveToEEPROM(void); void _saveToEEPROM(void);
void _checkInitialLoadComplete(bool failIfNoDefaultComponent); void _checkInitialLoadComplete(void);
/// First mapping is by component id /// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant /// Second mapping is parameter name, to Fact* in QVariant
...@@ -172,8 +169,6 @@ private: ...@@ -172,8 +169,6 @@ private:
bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether successful or not bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether successful or not
bool _waitingForDefaultComponent; ///< true: last chance wait for default component params bool _waitingForDefaultComponent; ///< true: last chance wait for default component params
bool _saveRequired; ///< true: _saveToEEPROM should be called bool _saveRequired; ///< true: _saveToEEPROM should be called
int _defaultComponentId;
QString _defaultComponentIdParam; ///< Parameter which identifies default component
QString _versionParam; ///< Parameter which contains parameter set version QString _versionParam; ///< Parameter which contains parameter set version
int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known
QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
......
...@@ -88,7 +88,6 @@ public: ...@@ -88,7 +88,6 @@ public:
void initializeVehicle (Vehicle* vehicle) final; void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final; bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final; void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYSID_SW_TYPE"); }
QString missionCommandOverrides (MAV_TYPE vehicleType) const; QString missionCommandOverrides (MAV_TYPE vehicleType) const;
QString getVersionParam (void) final { return QStringLiteral("SYSID_SW_MREV"); } QString getVersionParam (void) final { return QStringLiteral("SYSID_SW_MREV"); }
QString internalParameterMetaDataFile (Vehicle* vehicle) final; QString internalParameterMetaDataFile (Vehicle* vehicle) final;
......
...@@ -187,9 +187,6 @@ public: ...@@ -187,9 +187,6 @@ public:
/// false: Do not send first item to vehicle, sequence numbers must be adjusted /// false: Do not send first item to vehicle, sequence numbers must be adjusted
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
/// Returns the parameter that is used to identify the default component
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
/// Returns the parameter which is used to identify the version number of parameter set /// Returns the parameter which is used to identify the version number of parameter set
virtual QString getVersionParam(void) { return QString(); } virtual QString getVersionParam(void) { return QString(); }
......
...@@ -50,7 +50,6 @@ public: ...@@ -50,7 +50,6 @@ public:
void initializeVehicle (Vehicle* vehicle) final; void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final; bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final; void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYS_AUTOSTART"); }
QString missionCommandOverrides (MAV_TYPE vehicleType) const final; QString missionCommandOverrides (MAV_TYPE vehicleType) const final;
QString getVersionParam (void) final { return QString("SYS_PARAM_VER"); } QString getVersionParam (void) final { return QString("SYS_PARAM_VER"); }
QString internalParameterMetaDataFile (Vehicle* vehicle) final { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); } QString internalParameterMetaDataFile (Vehicle* vehicle) final { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
......
...@@ -279,7 +279,7 @@ void GeoFenceController::saveToFile(const QString& filename) ...@@ -279,7 +279,7 @@ void GeoFenceController::saveToFile(const QString& filename)
paramNames.append(params[i].value<Fact*>()->name()); paramNames.append(params[i].value<Fact*>()->name());
} }
if (paramNames.count() > 0) { if (paramNames.count() > 0) {
paramMgr->saveToJson(paramMgr->defaultComponentId(), paramNames, fenceFileObject); paramMgr->saveToJson(_activeVehicle->defaultComponentId(), paramNames, fenceFileObject);
} }
if (breachReturnEnabled()) { if (breachReturnEnabled()) {
......
...@@ -33,7 +33,10 @@ ParameterEditorController::ParameterEditorController(void) ...@@ -33,7 +33,10 @@ ParameterEditorController::ParameterEditorController(void)
_componentIds += QString("%1").arg(componentId); _componentIds += QString("%1").arg(componentId);
} }
_currentGroup = groupMap[_currentComponentId].keys()[0]; // Be careful about no parameters
if (groupMap.contains(_currentComponentId) && groupMap[_currentComponentId].size() != 0) {
_currentGroup = groupMap[_currentComponentId].keys()[0];
}
_updateParameters(); _updateParameters();
connect(this, &ParameterEditorController::searchTextChanged, this, &ParameterEditorController::_updateParameters); connect(this, &ParameterEditorController::searchTextChanged, this, &ParameterEditorController::_updateParameters);
......
...@@ -68,7 +68,7 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) ...@@ -68,7 +68,7 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
this); this);
} }
void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType) void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType)
{ {
if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || vehicleId == 0) { if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || vehicleId == 0) {
return; return;
...@@ -86,9 +86,10 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle ...@@ -86,9 +86,10 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
break; break;
} }
qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:vehicleMavlinkVersion:vehicleFirmwareType:vehicleType " qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleMavlinkVersion:vehicleFirmwareType:vehicleType "
<< link->getName() << link->getName()
<< vehicleId << vehicleId
<< componentId
<< vehicleMavlinkVersion << vehicleMavlinkVersion
<< vehicleFirmwareType << vehicleFirmwareType
<< vehicleType; << vehicleType;
...@@ -107,7 +108,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle ...@@ -107,7 +108,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
// return; // return;
// } // }
Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _joystickManager); Vehicle* vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _joystickManager);
connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1); connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1);
connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged); connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged);
......
...@@ -94,7 +94,7 @@ private slots: ...@@ -94,7 +94,7 @@ private slots:
void _setActiveVehiclePhase2(void); void _setActiveVehiclePhase2(void);
void _vehicleParametersReadyChanged(bool parametersReady); void _vehicleParametersReadyChanged(bool parametersReady);
void _sendGCSHeartbeat(void); void _sendGCSHeartbeat(void);
void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType); void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType);
private: private:
bool _vehicleExists(int vehicleId); bool _vehicleExists(int vehicleId);
......
...@@ -58,12 +58,14 @@ const int Vehicle::_lowBatteryAnnounceRepeatMSecs = 30 * 1000; ...@@ -58,12 +58,14 @@ const int Vehicle::_lowBatteryAnnounceRepeatMSecs = 30 * 1000;
Vehicle::Vehicle(LinkInterface* link, Vehicle::Vehicle(LinkInterface* link,
int vehicleId, int vehicleId,
int defaultComponentId,
MAV_AUTOPILOT firmwareType, MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType, MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager, FirmwarePluginManager* firmwarePluginManager,
JoystickManager* joystickManager) JoystickManager* joystickManager)
: FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json") : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json")
, _id(vehicleId) , _id(vehicleId)
, _defaultComponentId(defaultComponentId)
, _active(false) , _active(false)
, _offlineEditingVehicle(false) , _offlineEditingVehicle(false)
, _firmwareType(firmwareType) , _firmwareType(firmwareType)
...@@ -211,6 +213,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -211,6 +213,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
QObject* parent) QObject* parent)
: FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent) : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent)
, _id(0) , _id(0)
, _defaultComponentId(MAV_COMP_ID_ALL)
, _active(false) , _active(false)
, _offlineEditingVehicle(true) , _offlineEditingVehicle(true)
, _firmwareType(firmwareType) , _firmwareType(firmwareType)
...@@ -1347,7 +1350,7 @@ QGeoCoordinate Vehicle::homePosition(void) ...@@ -1347,7 +1350,7 @@ QGeoCoordinate Vehicle::homePosition(void)
void Vehicle::setArmed(bool armed) void Vehicle::setArmed(bool armed)
{ {
// We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks. // We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
sendMavCommand(defaultComponentId(), sendMavCommand(_defaultComponentId,
MAV_CMD_COMPONENT_ARM_DISARM, MAV_CMD_COMPONENT_ARM_DISARM,
true, // show error if fails true, // show error if fails
armed ? 1.0f : 0.0f); armed ? 1.0f : 0.0f);
...@@ -1428,7 +1431,7 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send ...@@ -1428,7 +1431,7 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send
dataStream.req_message_rate = rate; dataStream.req_message_rate = rate;
dataStream.start_stop = 1; // start dataStream.start_stop = 1; // start
dataStream.target_system = id(); dataStream.target_system = id();
dataStream.target_component = defaultComponentId(); dataStream.target_component = _defaultComponentId;
mavlink_msg_request_data_stream_encode_chan(_mavlink->getSystemId(), mavlink_msg_request_data_stream_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(), _mavlink->getComponentId(),
...@@ -1850,7 +1853,7 @@ void Vehicle::setGuidedMode(bool guidedMode) ...@@ -1850,7 +1853,7 @@ void Vehicle::setGuidedMode(bool guidedMode)
void Vehicle::emergencyStop(void) void Vehicle::emergencyStop(void)
{ {
sendMavCommand(defaultComponentId(), sendMavCommand(_defaultComponentId,
MAV_CMD_COMPONENT_ARM_DISARM, MAV_CMD_COMPONENT_ARM_DISARM,
true, // show error if fails true, // show error if fails
0.0f, 0.0f,
...@@ -2019,12 +2022,7 @@ QString Vehicle::firmwareVersionTypeString(void) const ...@@ -2019,12 +2022,7 @@ QString Vehicle::firmwareVersionTypeString(void) const
void Vehicle::rebootVehicle() void Vehicle::rebootVehicle()
{ {
sendMavCommand(defaultComponentId(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f); sendMavCommand(_defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f);
}
int Vehicle::defaultComponentId(void)
{
return _parameterManager->defaultComponentId();
} }
void Vehicle::setSoloFirmware(bool soloFirmware) void Vehicle::setSoloFirmware(bool soloFirmware)
...@@ -2039,7 +2037,7 @@ void Vehicle::setSoloFirmware(bool soloFirmware) ...@@ -2039,7 +2037,7 @@ void Vehicle::setSoloFirmware(bool soloFirmware)
// Temporarily removed, waiting for new command implementation // Temporarily removed, waiting for new command implementation
void Vehicle::motorTest(int motor, int percent, int timeoutSecs) void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
{ {
doCommandLongUnverified(defaultComponentId(), MAV_CMD_DO_MOTOR_TEST, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs); doCommandLongUnverified(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs);
} }
#endif #endif
...@@ -2113,6 +2111,14 @@ QStringList Vehicle::unhealthySensors(void) const ...@@ -2113,6 +2111,14 @@ QStringList Vehicle::unhealthySensors(void) const
return sensorList; return sensorList;
} }
void Vehicle::setOfflineEditingDefaultComponentId(int defaultComponentId)
{
if (_offlineEditingVehicle) {
_defaultComponentId = defaultComponentId;
} else {
qWarning() << "Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline";
}
}
const char* VehicleGPSFactGroup::_hdopFactName = "hdop"; const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop"; const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
...@@ -2141,12 +2147,12 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent) ...@@ -2141,12 +2147,12 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
void Vehicle::startMavlinkLog() void Vehicle::startMavlinkLog()
{ {
sendMavCommand(defaultComponentId(), MAV_CMD_LOGGING_START, false /* showError */); sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_START, false /* showError */);
} }
void Vehicle::stopMavlinkLog() void Vehicle::stopMavlinkLog()
{ {
sendMavCommand(defaultComponentId(), MAV_CMD_LOGGING_STOP, false /* showError */); sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_STOP, false /* showError */);
} }
void Vehicle::_ackMavlinkLogData(uint16_t sequence) void Vehicle::_ackMavlinkLogData(uint16_t sequence)
...@@ -2154,7 +2160,7 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence) ...@@ -2154,7 +2160,7 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence)
mavlink_message_t msg; mavlink_message_t msg;
mavlink_logging_ack_t ack; mavlink_logging_ack_t ack;
ack.sequence = sequence; ack.sequence = sequence;
ack.target_component = defaultComponentId(); ack.target_component = _defaultComponentId;
ack.target_system = id(); ack.target_system = id();
mavlink_msg_logging_ack_encode_chan( mavlink_msg_logging_ack_encode_chan(
_mavlink->getSystemId(), _mavlink->getSystemId(),
......
...@@ -191,6 +191,7 @@ class Vehicle : public FactGroup ...@@ -191,6 +191,7 @@ class Vehicle : public FactGroup
public: public:
Vehicle(LinkInterface* link, Vehicle(LinkInterface* link,
int vehicleId, int vehicleId,
int defaultComponentId,
MAV_AUTOPILOT firmwareType, MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType, MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager, FirmwarePluginManager* firmwarePluginManager,
...@@ -567,7 +568,10 @@ public: ...@@ -567,7 +568,10 @@ public:
bool soloFirmware(void) const { return _soloFirmware; } bool soloFirmware(void) const { return _soloFirmware; }
void setSoloFirmware(bool soloFirmware); void setSoloFirmware(bool soloFirmware);
int defaultComponentId(void); int defaultComponentId(void) { return _defaultComponentId; }
/// Sets the default component id for an offline editing vehicle
void setOfflineEditingDefaultComponentId(int defaultComponentId);
/// @return -1 = Unknown, Number of motors on vehicle /// @return -1 = Unknown, Number of motors on vehicle
int motorCount(void); int motorCount(void);
...@@ -736,6 +740,7 @@ private: ...@@ -736,6 +740,7 @@ private:
void _commonInit(void); void _commonInit(void);
int _id; ///< Mavlink system id int _id; ///< Mavlink system id
int _defaultComponentId;
bool _active; bool _active;
bool _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing bool _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
......
...@@ -283,7 +283,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -283,7 +283,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
mavlink_heartbeat_t heartbeat; mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat); mavlink_msg_heartbeat_decode(&message, &heartbeat);
emit vehicleHeartbeatInfo(link, message.sysid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type); emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
} }
// Increase receive counter // Increase receive counter
......
...@@ -130,7 +130,7 @@ protected: ...@@ -130,7 +130,7 @@ protected:
signals: signals:
/// Heartbeat received on link /// Heartbeat received on link
void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType); void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType);
/** @brief Message received and directly copied via signal */ /** @brief Message received and directly copied via signal */
void messageReceived(LinkInterface* link, mavlink_message_t message); void messageReceived(LinkInterface* link, mavlink_message_t message);
......
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