|
|
|
@ -20,6 +20,7 @@
@@ -20,6 +20,7 @@
|
|
|
|
|
|
|
|
|
|
#include <AP_Filesystem/AP_Filesystem.h> |
|
|
|
|
#include <AP_HAL/utility/sparse-endian.h> |
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h> |
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
@ -29,7 +30,14 @@ struct GCS_MAVLINK::ftp_state GCS_MAVLINK::ftp;
@@ -29,7 +30,14 @@ struct GCS_MAVLINK::ftp_state GCS_MAVLINK::ftp;
|
|
|
|
|
#define FTP_SESSION_TIMEOUT 3000 |
|
|
|
|
|
|
|
|
|
bool GCS_MAVLINK::ftp_init(void) { |
|
|
|
|
|
|
|
|
|
// check if ftp is disabled for memory savings
|
|
|
|
|
if (AP_BoardConfig::ftp_disabled()) { |
|
|
|
|
goto failed; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// we can simply check if we allocated everything we need
|
|
|
|
|
|
|
|
|
|
if (ftp.requests != nullptr) { |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|