Commit 750901fb authored by Gus Grubba's avatar Gus Grubba

Keep track of current vehicle's last known location.

parent 72b172b4
...@@ -285,6 +285,14 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void) ...@@ -285,6 +285,14 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void)
{ {
qCDebug(MultiVehicleManagerLog) << "_setActiveVehiclePhase2 _vehicleBeingSetActive" << _vehicleBeingSetActive; qCDebug(MultiVehicleManagerLog) << "_setActiveVehiclePhase2 _vehicleBeingSetActive" << _vehicleBeingSetActive;
//-- Keep track of current vehicle's coordinates
if(_activeVehicle) {
disconnect(_activeVehicle, &Vehicle::coordinateChanged, this, &MultiVehicleManager::_coordinateChanged);
}
if(_vehicleBeingSetActive) {
connect(_vehicleBeingSetActive, &Vehicle::coordinateChanged, this, &MultiVehicleManager::_coordinateChanged);
}
// Now we signal the new active vehicle // Now we signal the new active vehicle
_activeVehicle = _vehicleBeingSetActive; _activeVehicle = _vehicleBeingSetActive;
emit activeVehicleChanged(_activeVehicle); emit activeVehicleChanged(_activeVehicle);
...@@ -302,6 +310,12 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void) ...@@ -302,6 +310,12 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void)
} }
} }
void MultiVehicleManager::_coordinateChanged(QGeoCoordinate coordinate)
{
_lastKnownLocation = coordinate;
emit lastKnownLocationChanged();
}
void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady) void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady)
{ {
auto* paramMgr = qobject_cast<ParameterManager*>(sender()); auto* paramMgr = qobject_cast<ParameterManager*>(sender());
......
...@@ -47,6 +47,9 @@ public: ...@@ -47,6 +47,9 @@ public:
/// A disconnected vehicle used for offline editing. It will match the vehicle type specified in Settings. /// A disconnected vehicle used for offline editing. It will match the vehicle type specified in Settings.
Q_PROPERTY(Vehicle* offlineEditingVehicle READ offlineEditingVehicle CONSTANT) Q_PROPERTY(Vehicle* offlineEditingVehicle READ offlineEditingVehicle CONSTANT)
//-- The current vehicle's last known location
Q_PROPERTY(QGeoCoordinate lastKnownLocation READ lastKnownLocation NOTIFY lastKnownLocationChanged)
// Methods // Methods
Q_INVOKABLE Vehicle* getVehicleById(int vehicleId); Q_INVOKABLE Vehicle* getVehicleById(int vehicleId);
...@@ -78,24 +81,27 @@ public: ...@@ -78,24 +81,27 @@ public:
// Override from QGCTool // Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox); virtual void setToolbox(QGCToolbox *toolbox);
QGeoCoordinate lastKnownLocation () { return _lastKnownLocation; }
signals: signals:
void vehicleAdded(Vehicle* vehicle); void vehicleAdded (Vehicle* vehicle);
void vehicleRemoved(Vehicle* vehicle); void vehicleRemoved (Vehicle* vehicle);
void activeVehicleAvailableChanged(bool activeVehicleAvailable); void activeVehicleAvailableChanged (bool activeVehicleAvailable);
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable); void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable);
void activeVehicleChanged(Vehicle* activeVehicle); void activeVehicleChanged (Vehicle* activeVehicle);
void gcsHeartBeatEnabledChanged(bool gcsHeartBeatEnabled); void gcsHeartBeatEnabledChanged (bool gcsHeartBeatEnabled);
void lastKnownLocationChanged ();
void _deleteVehiclePhase2Signal(void); void _deleteVehiclePhase2Signal (void);
private slots: private slots:
void _deleteVehiclePhase1(Vehicle* vehicle); void _deleteVehiclePhase1 (Vehicle* vehicle);
void _deleteVehiclePhase2(void); void _deleteVehiclePhase2 (void);
void _setActiveVehiclePhase2(void); void _setActiveVehiclePhase2 (void);
void _vehicleParametersReadyChanged(bool parametersReady); void _vehicleParametersReadyChanged (bool parametersReady);
void _sendGCSHeartbeat(void); void _sendGCSHeartbeat (void);
void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType); void _vehicleHeartbeatInfo (LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType);
void _requestProtocolVersion(unsigned version); void _requestProtocolVersion (unsigned version);
void _coordinateChanged (QGeoCoordinate coordinate);
private: private:
bool _vehicleExists(int vehicleId); bool _vehicleExists(int vehicleId);
...@@ -115,6 +121,7 @@ private: ...@@ -115,6 +121,7 @@ private:
FirmwarePluginManager* _firmwarePluginManager; FirmwarePluginManager* _firmwarePluginManager;
JoystickManager* _joystickManager; JoystickManager* _joystickManager;
MAVLinkProtocol* _mavlinkProtocol; MAVLinkProtocol* _mavlinkProtocol;
QGeoCoordinate _lastKnownLocation;
QTimer _gcsHeartbeatTimer; ///< Timer to emit heartbeats QTimer _gcsHeartbeatTimer; ///< Timer to emit heartbeats
bool _gcsHeartbeatEnabled; ///< Enabled/disable heartbeat emission bool _gcsHeartbeatEnabled; ///< Enabled/disable heartbeat emission
......
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