Commit ef4ff0d2 authored by Don Gagne's avatar Don Gagne

Wait until parameter load complete for Mission Load

parent 4e0a8403
...@@ -45,8 +45,6 @@ MissionManager::MissionManager(Vehicle* vehicle) ...@@ -45,8 +45,6 @@ MissionManager::MissionManager(Vehicle* vehicle)
_ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds); _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout); connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout);
requestMissionItems();
} }
MissionManager::~MissionManager() MissionManager::~MissionManager()
......
...@@ -87,6 +87,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, ...@@ -87,6 +87,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType,
, _satelliteLock(0) , _satelliteLock(0)
, _updateCount(0) , _updateCount(0)
, _missionManager(NULL) , _missionManager(NULL)
, _missionManagerInitialRequestComplete(false)
, _armed(false) , _armed(false)
, _base_mode(0) , _base_mode(0)
, _custom_mode(0) , _custom_mode(0)
...@@ -110,7 +111,8 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, ...@@ -110,7 +111,8 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType,
_firmwarePlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _firmwarePlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
_autopilotPlugin = AutoPilotPluginManager::instance()->newAutopilotPluginForVehicle(this); _autopilotPlugin = AutoPilotPluginManager::instance()->newAutopilotPluginForVehicle(this);
connect(_autopilotPlugin, &AutoPilotPlugin::missingParametersChanged, this, &Vehicle::missingParametersChanged); connect(_autopilotPlugin, &AutoPilotPlugin::parametersReadyChanged, this, &Vehicle::_parametersReady);
connect(_autopilotPlugin, &AutoPilotPlugin::missingParametersChanged, this, &Vehicle::missingParametersChanged);
// Refresh timer // Refresh timer
connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate())); connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate()));
...@@ -1101,3 +1103,11 @@ void Vehicle::_mapTrajectoryStop() ...@@ -1101,3 +1103,11 @@ void Vehicle::_mapTrajectoryStop()
{ {
_mapTrajectoryTimer.stop(); _mapTrajectoryTimer.stop();
} }
void Vehicle::_parametersReady(bool parametersReady)
{
if (parametersReady && !_missionManagerInitialRequestComplete) {
_missionManagerInitialRequestComplete = true;
_missionManager->requestMissionItems();
}
}
...@@ -304,6 +304,7 @@ private slots: ...@@ -304,6 +304,7 @@ private slots:
void _sendMessage(mavlink_message_t message); void _sendMessage(mavlink_message_t message);
void _sendMessageMultipleNext(void); void _sendMessageMultipleNext(void);
void _addNewMapTrajectoryPoint(void); void _addNewMapTrajectoryPoint(void);
void _parametersReady(bool parametersReady);
void _handleTextMessage (int newCount); void _handleTextMessage (int newCount);
/** @brief Attitude from main autopilot / system state */ /** @brief Attitude from main autopilot / system state */
...@@ -409,7 +410,7 @@ private: ...@@ -409,7 +410,7 @@ private:
int _updateCount; int _updateCount;
MissionManager* _missionManager; MissionManager* _missionManager;
QmlObjectListModel _missionItems; bool _missionManagerInitialRequestComplete;
bool _armed; ///< true: vehicle is armed bool _armed; ///< true: vehicle is armed
uint8_t _base_mode; ///< base_mode from HEARTBEAT uint8_t _base_mode; ///< base_mode from HEARTBEAT
......
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