Commit 12025fd3 authored by Don Gagne's avatar Don Gagne

Fix HIL shutdown crash

parent ff6edbdc
...@@ -109,7 +109,7 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle) ...@@ -109,7 +109,7 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
} }
vehicle->setActive(false); vehicle->setActive(false);
vehicle->uas()->clearVehicle(); vehicle->uas()->shutdownVehicle();
// First we must signal that a vehicle is no longer available. // First we must signal that a vehicle is no longer available.
_activeVehicleAvailable = false; _activeVehicleAvailable = false;
......
...@@ -1057,7 +1057,7 @@ void Vehicle::setFlightMode(const QString& flightMode) ...@@ -1057,7 +1057,7 @@ void Vehicle::setFlightMode(const QString& flightMode)
mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, custom_mode); mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, custom_mode);
sendMessage(msg); sendMessage(msg);
} else { } else {
qCWarning(VehicleLog) << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode; qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
} }
} }
......
...@@ -193,23 +193,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi ...@@ -193,23 +193,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi
statusTimeout.start(500); statusTimeout.start(500);
} }
/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* by calling writeSettings.
*/
UAS::~UAS()
{
#ifndef __mobile__
stopHil();
if (simulation) {
// wait for the simulator to exit
simulation->wait();
simulation->disconnectSimulation();
simulation->deleteLater();
}
#endif
}
/** /**
* @ return the id of the uas * @ return the id of the uas
*/ */
...@@ -2216,3 +2199,17 @@ void UAS::_say(const QString& text, int severity) ...@@ -2216,3 +2199,17 @@ void UAS::_say(const QString& text, int severity)
if (!qgcApp()->runningUnitTests()) if (!qgcApp()->runningUnitTests())
qgcApp()->toolbox()->audioOutput()->say(text, severity); qgcApp()->toolbox()->audioOutput()->say(text, severity);
} }
void UAS::shutdownVehicle(void)
{
#ifndef __mobile__
stopHil();
if (simulation) {
// wait for the simulator to exit
simulation->wait();
simulation->disconnectSimulation();
simulation->deleteLater();
}
#endif
_vehicle = NULL;
}
...@@ -64,7 +64,6 @@ class UAS : public UASInterface ...@@ -64,7 +64,6 @@ class UAS : public UASInterface
Q_OBJECT Q_OBJECT
public: public:
UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager); UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager);
~UAS();
float lipoFull; ///< 100% charged voltage float lipoFull; ///< 100% charged voltage
float lipoEmpty; ///< Discharged voltage float lipoEmpty; ///< Discharged voltage
...@@ -100,7 +99,8 @@ public: ...@@ -100,7 +99,8 @@ public:
Q_PROPERTY(double satRawVDOP READ getSatRawVDOP NOTIFY satRawVDOPChanged) Q_PROPERTY(double satRawVDOP READ getSatRawVDOP NOTIFY satRawVDOPChanged)
Q_PROPERTY(double satRawCOG READ getSatRawCOG NOTIFY satRawCOGChanged) Q_PROPERTY(double satRawCOG READ getSatRawCOG NOTIFY satRawCOGChanged)
void clearVehicle(void) { _vehicle = NULL; } /// Vehicle is about to go away
void shutdownVehicle(void);
void setGroundSpeed(double val) void setGroundSpeed(double val)
{ {
......
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