|
|
@ -31,7 +31,7 @@ APMRallyPointManager::~APMRallyPointManager() |
|
|
|
|
|
|
|
|
|
|
|
void APMRallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) |
|
|
|
void APMRallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (_vehicle->isOfflineEditingVehicle()) { |
|
|
|
if (_vehicle->isOfflineEditingVehicle() || !rallyPointsSupported()) { |
|
|
|
return; |
|
|
|
return; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -53,7 +53,7 @@ void APMRallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) |
|
|
|
|
|
|
|
|
|
|
|
void APMRallyPointManager::loadFromVehicle(void) |
|
|
|
void APMRallyPointManager::loadFromVehicle(void) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (_vehicle->isOfflineEditingVehicle() || _readTransactionInProgress) { |
|
|
|
if (_vehicle->isOfflineEditingVehicle() || !rallyPointsSupported() || _readTransactionInProgress) { |
|
|
|
return; |
|
|
|
return; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -144,3 +144,8 @@ bool APMRallyPointManager::inProgress(void) const |
|
|
|
{ |
|
|
|
{ |
|
|
|
return _readTransactionInProgress || _writeTransactionInProgress; |
|
|
|
return _readTransactionInProgress || _writeTransactionInProgress; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
bool APMRallyPointManager::rallyPointsSupported(void) const |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
return _vehicle->parameterManager()->parameterExists(_vehicle->defaultComponentId(), _rallyTotalParam); |
|
|
|
|
|
|
|
} |
|
|
|