Unverified Commit 2c6f5625 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7076 from DonLakeFlyer/AutoLoad

AutoLoad: Not loading GeoFence or Rally points correctly
parents 7f958639 360bfab5
......@@ -33,22 +33,23 @@ const char* PlanMasterController::kJsonGeoFenceObjectKey = "geoFence";
const char* PlanMasterController::kJsonRallyPointsObjectKey = "rallyPoints";
PlanMasterController::PlanMasterController(QObject* parent)
: QObject (parent)
, _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
, _controllerVehicle (new Vehicle(
: QObject (parent)
, _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
, _controllerVehicle (new Vehicle(
static_cast<MAV_AUTOPILOT>(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt()),
static_cast<MAV_TYPE>(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt()),
qgcApp()->toolbox()->firmwarePluginManager()))
, _managerVehicle (_controllerVehicle)
, _flyView (true)
, _offline (true)
, _missionController (this)
, _geoFenceController (this)
, _rallyPointController (this)
, _loadGeoFence (false)
, _loadRallyPoints (false)
, _sendGeoFence (false)
, _sendRallyPoints (false)
, _managerVehicle (_controllerVehicle)
, _flyView (true)
, _offline (true)
, _missionController (this)
, _geoFenceController (this)
, _rallyPointController (this)
, _loadGeoFence (false)
, _loadRallyPoints (false)
, _sendGeoFence (false)
, _sendRallyPoints (false)
, _deleteWhenSendCompleted (false)
{
connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
......@@ -86,9 +87,10 @@ void PlanMasterController::start(bool flyView)
#endif
}
void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle)
void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle, bool deleteWhenSendCompleted)
{
_flyView = true;
_deleteWhenSendCompleted = deleteWhenSendCompleted;
_missionController.start(_flyView);
_geoFenceController.start(_flyView);
_rallyPointController.start(_flyView);
......@@ -264,6 +266,9 @@ void PlanMasterController::_sendGeoFenceComplete(void)
void PlanMasterController::_sendRallyPointsComplete(void)
{
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Point send complete";
if (_deleteWhenSendCompleted) {
this->deleteLater();
}
}
void PlanMasterController::sendToVehicle(void)
......@@ -535,10 +540,9 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi
{
// Use a transient PlanMasterController to accomplish this
PlanMasterController* controller = new PlanMasterController();
controller->startStaticActiveVehicle(vehicle);
controller->startStaticActiveVehicle(vehicle, true /* deleteWhenSendCompleted */);
controller->loadFromFile(filename);
controller->sendToVehicle();
delete controller;
}
void PlanMasterController::_showPlanFromManagerVehicle(void)
......
......@@ -49,7 +49,8 @@ public:
Q_INVOKABLE void start(bool flyView);
/// Starts the controller using a single static active vehicle. Will not track global active vehicle changes.
Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle);
/// @param deleteWhenSendCmplete The PlanMasterController object should be deleted after the first send is completed.
Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle, bool deleteWhenSendCompleted = false);
/// Determines if the plan has all data needed to be saved or sent to the vehicle. Currently the only case where this
/// would return false is when it is still waiting on terrain data to determine correct altitudes.
......@@ -127,5 +128,6 @@ private:
bool _sendGeoFence;
bool _sendRallyPoints;
QString _currentPlanFile;
bool _deleteWhenSendCompleted;
};
......@@ -203,15 +203,15 @@ QString RallyPointController::editorQml(void) const
return _rallyPointManager->editorQml();
}
void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPoints)
void RallyPointController::_managerLoadComplete(void)
{
// Fly view always reloads on _loadComplete
// Plan view only reloads on _loadComplete if specifically requested
if (_flyView || _itemsRequested) {
_points.clearAndDeleteContents();
QObjectList pointList;
for (int i=0; i<rgPoints.count(); i++) {
pointList.append(new RallyPoint(rgPoints[i], this));
for (int i=0; i<_rallyPointManager->points().count(); i++) {
pointList.append(new RallyPoint(_rallyPointManager->points()[i], this));
}
_points.swapObjectList(pointList);
setDirty(false);
......@@ -224,7 +224,7 @@ void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPo
void RallyPointController::_managerSendComplete(bool error)
{
// Fly view always reloads after send
if (!error && !_flyView) {
if (!error && _flyView) {
showPlanFromManagerVehicle();
}
}
......@@ -317,6 +317,7 @@ bool RallyPointController::showPlanFromManagerVehicle (void)
} else {
qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle: sync complete";
_itemsRequested = true;
_managerLoadComplete();
return false;
}
}
......
......@@ -61,7 +61,7 @@ signals:
void loadComplete(void);
private slots:
void _managerLoadComplete(const QList<QGeoCoordinate> rgPoints);
void _managerLoadComplete(void);
void _managerSendComplete(bool error);
void _managerRemoveAllComplete(bool error);
void _setFirstPointCurrent(void);
......
......@@ -21,7 +21,7 @@ RallyPointManager::RallyPointManager(Vehicle* vehicle)
connect(&_planManager, &PlanManager::inProgressChanged, this, &RallyPointManager::inProgressChanged);
connect(&_planManager, &PlanManager::error, this, &RallyPointManager::error);
connect(&_planManager, &PlanManager::removeAllComplete, this, &RallyPointManager::removeAllComplete);
connect(&_planManager, &PlanManager::sendComplete, this, &RallyPointManager::sendComplete);
connect(&_planManager, &PlanManager::sendComplete, this, &RallyPointManager::_sendComplete);
connect(&_planManager, &PlanManager::newMissionItemsAvailable, this, &RallyPointManager::_planManagerLoadComplete);
}
......@@ -45,8 +45,12 @@ void RallyPointManager::loadFromVehicle(void)
void RallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints)
{
QList<MissionItem*> rallyItems;
_rgSendPoints.clear();
for (const QGeoCoordinate& rallyPoint: rgPoints) {
_rgSendPoints.append(rallyPoint);
}
QList<MissionItem*> rallyItems;
for (int i=0; i<rgPoints.count(); i++) {
MissionItem* item = new MissionItem(0,
......@@ -100,5 +104,16 @@ void RallyPointManager::_planManagerLoadComplete(bool removeAllRequested)
}
emit loadComplete(_rgPoints);
emit loadComplete();
}
void RallyPointManager::_sendComplete(bool error)
{
if (error) {
_rgPoints.clear();
} else {
_rgPoints = _rgSendPoints;
}
_rgSendPoints.clear();
emit sendComplete(error);
}
......@@ -62,13 +62,14 @@ public:
} ErrorCode_t;
signals:
void loadComplete (const QList<QGeoCoordinate> rgPoints);
void loadComplete (void);
void inProgressChanged (bool inProgress);
void error (int errorCode, const QString& errorMsg);
void removeAllComplete (bool error);
void sendComplete (bool error);
private slots:
void _sendComplete (bool error);
void _planManagerLoadComplete (bool removeAllRequested);
protected:
......@@ -77,6 +78,7 @@ protected:
Vehicle* _vehicle;
PlanManager _planManager;
QList<QGeoCoordinate> _rgPoints;
QList<QGeoCoordinate> _rgSendPoints;
};
#endif
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