|
|
|
@ -162,35 +162,42 @@ bool ArduCopterFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabil
@@ -162,35 +162,42 @@ bool ArduCopterFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabil
|
|
|
|
|
|
|
|
|
|
void ArduCopterFirmwarePlugin::guidedModeRTL(Vehicle* vehicle) |
|
|
|
|
{ |
|
|
|
|
vehicle->setFlightMode("RTL"); |
|
|
|
|
_setFlightModeAndValidate(vehicle, "RTL"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle) |
|
|
|
|
{ |
|
|
|
|
vehicle->setFlightMode("Land"); |
|
|
|
|
_setFlightModeAndValidate(vehicle, "Land"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle) |
|
|
|
|
{ |
|
|
|
|
_guidedModeTakeoff(vehicle); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool ArduCopterFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle) |
|
|
|
|
{ |
|
|
|
|
QString takeoffAltParam("PILOT_TKOFF_ALT"); |
|
|
|
|
|
|
|
|
|
if (!vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, takeoffAltParam)) { |
|
|
|
|
qgcApp()->showMessage(tr("Unable to takeoff, %1 parameter missing.").arg(takeoffAltParam)); |
|
|
|
|
return; |
|
|
|
|
float takeoffAlt = 0; |
|
|
|
|
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, takeoffAltParam)) { |
|
|
|
|
Fact* takeoffAltFact = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, takeoffAltParam); |
|
|
|
|
takeoffAlt = takeoffAltFact->rawValue().toDouble(); |
|
|
|
|
} |
|
|
|
|
Fact* takeoffAltFact = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, takeoffAltParam); |
|
|
|
|
float takeoffAlt = takeoffAltFact->rawValue().toDouble(); |
|
|
|
|
if (takeoffAlt <= 0) { |
|
|
|
|
takeoffAlt = 2.5; |
|
|
|
|
} else { |
|
|
|
|
takeoffAlt /= 100; // centimeters -> meters
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
setGuidedMode(vehicle, true); |
|
|
|
|
if (!_setFlightModeAndValidate(vehicle, "Guided")) { |
|
|
|
|
qgcApp()->showMessage(tr("Unable to takeoff: Vehicle failed to change to Guided mode.")); |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!_armVehicleAndValidate(vehicle)) { |
|
|
|
|
qgcApp()->showMessage(tr("Unable to takeoff: Vehicle failed to arm.")); |
|
|
|
|
return; |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
vehicle->sendMavCommand(vehicle->defaultComponentId(), |
|
|
|
@ -198,6 +205,8 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
@@ -198,6 +205,8 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
|
|
|
|
|
true, // show error
|
|
|
|
|
0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, |
|
|
|
|
takeoffAlt); |
|
|
|
|
|
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void ArduCopterFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) |
|
|
|
@ -246,13 +255,13 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
@@ -246,13 +255,13 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
|
|
|
|
|
|
|
|
|
|
void ArduCopterFirmwarePlugin::pauseVehicle(Vehicle* vehicle) |
|
|
|
|
{ |
|
|
|
|
vehicle->setFlightMode("Brake"); |
|
|
|
|
_setFlightModeAndValidate(vehicle, "Brake"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void ArduCopterFirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode) |
|
|
|
|
{ |
|
|
|
|
if (guidedMode) { |
|
|
|
|
vehicle->setFlightMode("Guided"); |
|
|
|
|
_setFlightModeAndValidate(vehicle, "Guided"); |
|
|
|
|
} else { |
|
|
|
|
pauseVehicle(vehicle); |
|
|
|
|
} |
|
|
|
@ -293,25 +302,29 @@ void ArduCopterFirmwarePlugin::startMission(Vehicle* vehicle)
@@ -293,25 +302,29 @@ void ArduCopterFirmwarePlugin::startMission(Vehicle* vehicle)
|
|
|
|
|
double currentAlt = vehicle->altitudeRelative()->rawValue().toDouble(); |
|
|
|
|
|
|
|
|
|
if (!vehicle->flying()) { |
|
|
|
|
guidedModeTakeoff(vehicle); |
|
|
|
|
|
|
|
|
|
// Wait for vehicle to get off ground before switching to auto
|
|
|
|
|
bool didTakeoff = false; |
|
|
|
|
for (int i=0; i<50; i++) { |
|
|
|
|
if (vehicle->altitudeRelative()->rawValue().toDouble() >= currentAlt + 1.0) { |
|
|
|
|
didTakeoff = true; |
|
|
|
|
break; |
|
|
|
|
if (_guidedModeTakeoff(vehicle)) { |
|
|
|
|
|
|
|
|
|
// Wait for vehicle to get off ground before switching to auto (10 seconds)
|
|
|
|
|
bool didTakeoff = false; |
|
|
|
|
for (int i=0; i<100; i++) { |
|
|
|
|
if (vehicle->altitudeRelative()->rawValue().toDouble() >= currentAlt + 1.0) { |
|
|
|
|
didTakeoff = true; |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
QGC::SLEEP::msleep(100); |
|
|
|
|
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); |
|
|
|
|
} |
|
|
|
|
QGC::SLEEP::msleep(100); |
|
|
|
|
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!didTakeoff) { |
|
|
|
|
qgcApp()->showMessage(QStringLiteral("Unable to switch to Auto. Vehicle takeoff failed.")); |
|
|
|
|
return; |
|
|
|
|
if (!didTakeoff) { |
|
|
|
|
qgcApp()->showMessage(QStringLiteral("Unable to start mission. Vehicle takeoff failed.")); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
vehicle->setFlightMode(missionFlightMode()); |
|
|
|
|
if (!_setFlightModeAndValidate(vehicle, missionFlightMode())) { |
|
|
|
|
qgcApp()->showMessage(QStringLiteral("Unable to start mission. Vehicle failed to change to auto.")); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|