diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 270fb99d48094bc8d096dd74c32e0cc2f29cab11..8860e98c0e34b11593ad84aa959ac4cb5c86159d 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -133,8 +133,6 @@ void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle) vehicle->setFlightMode("Land"); } -#if 0 -// WIP void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle) { if (!_armVehicle(vehicle)) { @@ -148,7 +146,6 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle) 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 2.5); } -#endif void ArduCopterFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) { diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 8b771c110dcb7d0191f0fca406e3273179ad1da1..2d5414db0e99f344a7a3ce374156a1a9073b2215 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -58,10 +58,7 @@ public: void pauseVehicle(Vehicle* vehicle) final; void guidedModeRTL(Vehicle* vehicle) final; void guidedModeLand(Vehicle* vehicle) final; -#if 0 - // WIP void guidedModeTakeoff(Vehicle* vehicle) final; -#endif void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) final; void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) final; const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }