Commit 837de8bb authored by Don Gagne's avatar Don Gagne

Merge pull request #1892 from DonLakeFlyer/MissionManager

Take MissionManager off separate thread
parents 9e6e153e 7199e9c4
...@@ -167,6 +167,20 @@ QGCView { ...@@ -167,6 +167,20 @@ QGCView {
onTriggered: controller.saveMissionToFile() onTriggered: controller.saveMissionToFile()
} }
MenuSeparator { }
MenuItem {
text: "Move to current vehicle position"
enabled: activeVehicle && activeVehicle.latitude != 0 && activeVehicle.longitude != 0
property var activeVehicle: multiVehicleManager.activeVehicle
onTriggered: {
editorMap.latitude = activeVehicle.latitude
editorMap.longitude = activeVehicle.longitude
}
}
} }
} }
......
...@@ -31,44 +31,26 @@ ...@@ -31,44 +31,26 @@
QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog") QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
MissionManager::MissionManager(Vehicle* vehicle) MissionManager::MissionManager(Vehicle* vehicle)
: QThread() : _vehicle(vehicle)
, _vehicle(vehicle)
, _cMissionItems(0) , _cMissionItems(0)
, _canEdit(true) , _canEdit(true)
, _ackTimeoutTimer(NULL) , _ackTimeoutTimer(NULL)
, _retryAck(AckNone) , _retryAck(AckNone)
{ {
moveToThread(this);
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived); connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived);
connect(this, &MissionManager::_writeMissionItemsOnThread, this, &MissionManager::_writeMissionItems);
connect(this, &MissionManager::_requestMissionItemsOnThread, this, &MissionManager::_requestMissionItems);
start();
}
MissionManager::~MissionManager()
{
}
void MissionManager::run(void)
{
_ackTimeoutTimer = new QTimer(this); _ackTimeoutTimer = new QTimer(this);
_ackTimeoutTimer->setSingleShot(true); _ackTimeoutTimer->setSingleShot(true);
_ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds); _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout); connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout);
_requestMissionItems(); requestMissionItems();
exec();
} }
void MissionManager::requestMissionItems(void) MissionManager::~MissionManager()
{ {
emit _requestMissionItemsOnThread();
} }
void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems) void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
...@@ -78,10 +60,28 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems) ...@@ -78,10 +60,28 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
_missionItems.append(new MissionItem(*qobject_cast<const MissionItem*>(missionItems[i]))); _missionItems.append(new MissionItem(*qobject_cast<const MissionItem*>(missionItems[i])));
} }
emit _writeMissionItemsOnThread(); qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
if (inProgress()) {
qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
// FIXME: Better error handling
return;
}
mavlink_message_t message;
mavlink_mission_count_t missionCount;
missionCount.target_system = _vehicle->id();
missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionCount.count = _missionItems.count();
mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount);
_vehicle->sendMessage(message);
_startAckTimeout(AckMissionRequest, message);
} }
void MissionManager::_requestMissionItems(void) void MissionManager::requestMissionItems(void)
{ {
qCDebug(MissionManagerLog) << "_requestMissionItems"; qCDebug(MissionManagerLog) << "_requestMissionItems";
...@@ -173,7 +173,7 @@ void MissionManager::_handleMissionCount(const mavlink_message_t& message) ...@@ -173,7 +173,7 @@ void MissionManager::_handleMissionCount(const mavlink_message_t& message)
qCDebug(MissionManagerLog) << "_handleMissionCount count:" << _cMissionItems; qCDebug(MissionManagerLog) << "_handleMissionCount count:" << _cMissionItems;
if (_cMissionItems == 0) { if (_cMissionItems == 0) {
_sendTransactionComplete(); emit newMissionItemsAvailable();
} else { } else {
_requestNextMissionItem(0); _requestNextMissionItem(0);
} }
...@@ -251,29 +251,6 @@ void MissionManager::_clearMissionItems(void) ...@@ -251,29 +251,6 @@ void MissionManager::_clearMissionItems(void)
_missionItems.clear(); _missionItems.clear();
} }
void MissionManager::_writeMissionItems(void)
{
qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
if (inProgress()) {
qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
// FIXME: Better error handling
return;
}
mavlink_message_t message;
mavlink_mission_count_t missionCount;
missionCount.target_system = _vehicle->id();
missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionCount.count = _missionItems.count();
mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount);
_vehicle->sendMessage(message);
_startAckTimeout(AckMissionRequest, message);
}
void MissionManager::_handleMissionRequest(const mavlink_message_t& message) void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
{ {
mavlink_mission_request_t missionRequest; mavlink_mission_request_t missionRequest;
......
...@@ -38,7 +38,7 @@ class Vehicle; ...@@ -38,7 +38,7 @@ class Vehicle;
Q_DECLARE_LOGGING_CATEGORY(MissionManagerLog) Q_DECLARE_LOGGING_CATEGORY(MissionManagerLog)
class MissionManager : public QThread class MissionManager : public QObject
{ {
Q_OBJECT Q_OBJECT
...@@ -73,10 +73,6 @@ signals: ...@@ -73,10 +73,6 @@ signals:
void canEditChanged(bool canEdit); void canEditChanged(bool canEdit);
void newMissionItemsAvailable(void); void newMissionItemsAvailable(void);
// Internal signals
void _requestMissionItemsOnThread(void);
void _writeMissionItemsOnThread(void);
private slots: private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message); void _mavlinkMessageReceived(const mavlink_message_t& message);
void _ackTimeout(void); void _ackTimeout(void);
...@@ -98,12 +94,7 @@ private: ...@@ -98,12 +94,7 @@ private:
void _handleMissionAck(const mavlink_message_t& message); void _handleMissionAck(const mavlink_message_t& message);
void _requestNextMissionItem(int sequenceNumber); void _requestNextMissionItem(int sequenceNumber);
void _clearMissionItems(void); void _clearMissionItems(void);
void _requestMissionItems(void);
void _writeMissionItems(void);
// Overrides from QThread
void run(void);
private: private:
Vehicle* _vehicle; Vehicle* _vehicle;
......
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