Commit b08e6619 authored by Valentin Platzgummer's avatar Valentin Platzgummer

working on sync WiMA many way-points problem

parent 3b25253b
......@@ -291,25 +291,6 @@ bool WimaController::forceUploadToVehicle()
for (int i = 0; i < _currentMissionItems.count(); i++){
SimpleMissionItem *item = _currentMissionItems.value<SimpleMissionItem *>(i);
_missionController->insertSimpleMissionItem(*item, visuals->count());
if (item->command() == MAV_CMD_DO_CHANGE_SPEED) {
qWarning() << item->missionItem().param2();
}
}
qWarning("blah");
for (int i = 0; i < _missionController->visualItems()->count(); i++){
SimpleMissionItem *item = _missionController->visualItems()->value<SimpleMissionItem*>(i);
if (item == nullptr)
continue;
if (item->command() == MAV_CMD_DO_CHANGE_SPEED) {
qWarning() << item->missionItem().param2();
}
}
for (int i = 0; i < _missionController->visualItems()->count(); i++){
SimpleMissionItem *item = _missionController->visualItems()->value<SimpleMissionItem*>(i);
if (item == nullptr)
continue;
qWarning() << i << ":" << item->command();
}
_masterController->sendToVehicle();
......@@ -503,10 +484,10 @@ bool WimaController::fetchContainerData()
return false;
}
WimaPlanData planData = _container->pull();
QSharedPointer<const WimaPlanData> planData = _container->pull();
// extract list with WimaAreas
QList<const WimaAreaData*> areaList = planData.areaList();
QList<const WimaAreaData*> areaList = planData->areaList();
int areaCounter = 0;
int numAreas = 4; // extract only numAreas Areas, if there are more they are invalid and ignored
......@@ -550,7 +531,7 @@ bool WimaController::fetchContainerData()
}
// extract mission items
QList<MissionItem> tempMissionItems = planData.missionItems();
QList<QSharedPointer<const MissionItem>> tempMissionItems = planData->missionItems();
if (tempMissionItems.size() < 1)
return false;
......@@ -560,7 +541,7 @@ bool WimaController::fetchContainerData()
// create SimpleMissionItem by using _missionController
for ( int i = 0; i < tempMissionItems.size(); i++) {
_missionController->insertSimpleMissionItem(tempMissionItems[i], missionControllerVisualItems->count());
_missionController->insertSimpleMissionItem(*tempMissionItems[i], missionControllerVisualItems->count());
}
// copy mission items from _missionController to _missionItems
for ( int i = 1; i < missionControllerVisualItems->count(); i++) {
......
......@@ -2,7 +2,6 @@
WimaDataContainer::WimaDataContainer(QObject *parent)
: QObject (parent)
, _planData (this /* parent */)
{
}
......@@ -15,7 +14,7 @@ WimaDataContainer::WimaDataContainer(QObject *parent)
*
* \sa WimaPlanData
*/
void WimaDataContainer::push(const WimaPlanData &planData)
void WimaDataContainer::push(QSharedPointer<const WimaPlanData> planData)
{
_planData = planData;
......@@ -29,7 +28,7 @@ void WimaDataContainer::push(const WimaPlanData &planData)
*
* \sa WimaPlanData
*/
const WimaPlanData &WimaDataContainer::pull() const
QSharedPointer<const WimaPlanData> WimaDataContainer::pull() const
{
return _planData;
}
......
......@@ -18,11 +18,11 @@ signals:
void newDataAvailable(void);
public slots:
void push(const WimaPlanData &planData);
const WimaPlanData &pull() const;
void push(QSharedPointer<const WimaPlanData> planData);
QSharedPointer<const WimaPlanData> pull() const;
private:
WimaPlanData _planData;
QSharedPointer<const WimaPlanData> _planData;
};
......@@ -102,10 +102,8 @@ void WimaPlanData::append(const WimaMeasurementAreaData &areaData)
void WimaPlanData::append(const QList<MissionItem *> &missionItems)
{
for (MissionItem *item : missionItems) {
MissionItem copy = MissionItem(*item, this);
_missionItems.append(copy);
}
for (auto item : missionItems)
_missionItems.append(QSharedPointer<const MissionItem>(item));
}
/*!
......@@ -124,7 +122,7 @@ QList<const WimaAreaData *> WimaPlanData::areaList() const
return _areaList;
}
QList<MissionItem> WimaPlanData::missionItems() const
QList<QSharedPointer<const MissionItem>> WimaPlanData::missionItems() const
{
return _missionItems;
}
......
......@@ -22,11 +22,11 @@ public:
void append(const WimaServiceAreaData &areaData);
void append(const WimaCorridorData &areaData);
void append(const WimaMeasurementAreaData &areaData);
void append(const QList<MissionItem *> &missionItems);
void append(const QList<MissionItem *> &missionItems);
void clear();
QList<const WimaAreaData *> areaList() const;
QList<MissionItem> missionItems() const;
QList<QSharedPointer<const MissionItem>> missionItems() const;
......@@ -41,7 +41,7 @@ private:
WimaServiceAreaData _serviceArea;
WimaCorridorData _corridor;
WimaMeasurementAreaData _measurementArea;
QList<const WimaAreaData*> _areaList;
QList<const WimaAreaData *> _areaList;
QList<MissionItem> _missionItems;
QList<QSharedPointer<const MissionItem>> _missionItems;
};
......@@ -649,8 +649,7 @@ void WimaPlaner::pushToContainer()
if (_container != nullptr) {
if (!_readyForSync)
return;
WimaPlanData planData = toPlanData();
_container->push(planData);
_container->push(toPlanData());
setSyncronizedWithController(true);
} else {
qWarning("WimaPlaner::uploadToContainer(): no container assigned.");
......@@ -703,27 +702,24 @@ void WimaPlaner::setInteractive()
*
* \sa WimaController, WimaPlanData
*/
WimaPlanData WimaPlaner::toPlanData()
QSharedPointer<WimaPlanData> WimaPlaner::toPlanData()
{
WimaPlanData planData;
//WimaPlanData *data = new WimaPlanData(nullptr);
QSharedPointer<WimaPlanData> planData;
// store areas
planData.append(WimaMeasurementAreaData(_measurementArea));
planData.append(WimaServiceAreaData(_serviceArea));
planData.append(WimaCorridorData(_corridor));
planData.append(WimaJoinedAreaData(_joinedArea));
planData->append(WimaMeasurementAreaData(_measurementArea));
planData->append(WimaServiceAreaData(_serviceArea));
planData->append(WimaCorridorData(_corridor));
planData->append(WimaJoinedAreaData(_joinedArea));
// convert mission items to mavlink commands
QObject deleteObject; // used to automatically delete content of rgMissionItems after this function call
QList<MissionItem*> rgMissionItems;
QmlObjectListModel *visualItems = _missionController->visualItems();
QmlObjectListModel visualItemsToCopy;
for (int i = _arrivalPathLength+1; i < visualItems->count()-_returnPathLength; i++)
visualItemsToCopy.append(visualItems->get(i));
MissionController::convertToMissionItems(&visualItemsToCopy, rgMissionItems, &deleteObject);
MissionController::convertToMissionItems(visualItems, rgMissionItems, nullptr);
// store mavlink commands
planData.append(rgMissionItems);
planData->append(rgMissionItems);
return planData;
}
......
......@@ -142,10 +142,10 @@ signals:
void joinedAreaValidChanged();
private:
// Member Functions
WimaPlanData toPlanData();
void setSyncronizedWithController (bool sync);
void setReadyForSync (bool ready);
void setJoinedAreaValid (bool valid);
QSharedPointer<WimaPlanData> toPlanData ();
void setSyncronizedWithController (bool sync);
void setReadyForSync (bool ready);
void setJoinedAreaValid (bool valid);
// Member Variables
PlanMasterController *_masterController;
......
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