diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 3cf264ce3ec99..6bcae45590ba1 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -331,6 +331,7 @@ def __init__(self, Feature('MAVLink', 'AP_MAVLINK_SERVO_RELAY_ENABLED', 'AP_MAVLINK_SERVO_RELAY_ENABLED', 'Enable handling of ServoRelay mavlink messages', 0, 'SERVORELAY_EVENTS'), # noqa Feature('MAVLink', 'AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'Enable handling of Serial Control mavlink messages', 0, None), # noqa Feature('MAVLink', 'AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', 'AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', 'Enable handling of MISSION_REQUEST mavlink messages', 0, None), # noqa + Feature('MAVLink', 'AP_MAVLINK_FTP_ENABLED', 'AP_MAVLINK_FTP_ENABLED', 'Enable MAVLink FTP Protocol', 0, None), # noqa Feature('Developer', 'KILL_IMU', 'AP_INERTIALSENSOR_KILL_IMU_ENABLED', 'Allow IMUs to be disabled at runtime', 0, None), Feature('Developer', 'CRASHCATCHER', 'AP_CRASHDUMP_ENABLED', 'Enable CrashCatcher', 0, None), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 5a8665bf7faf7..cf129ae4b787f 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -232,6 +232,8 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_MAVLINK_SERVO_RELAY_ENABLED', 'GCS_MAVLINK::handle_servorelay_message'), ('AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'GCS_MAVLINK::handle_serial_control'), ('AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', 'GCS_MAVLINK::handle_mission_request\b'), + ('AP_MAVLINK_FTP_ENABLED', 'GCS_MAVLINK::ftp_worker'), + ('AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'AP_DroneCAN::SRV_send_himark'), ('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'), ('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'), diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 736cadfa053a9..52f728c9d293f 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -941,6 +941,7 @@ class GCS_MAVLINK uint8_t send_parameter_async_replies(); +#if AP_MAVLINK_FTP_ENABLED enum class FTP_OP : uint8_t { None = 0, TerminateSession = 1, @@ -1016,6 +1017,7 @@ class GCS_MAVLINK bool send_ftp_reply(const pending_ftp &reply); void ftp_worker(void); void ftp_push_replies(pending_ftp &reply); +#endif // AP_MAVLINK_FTP_ENABLED void send_distance_sensor(const class AP_RangeFinder_Backend *sensor, const uint8_t instance) const; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a4d700c6d478e..b04f34bd751f8 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1156,10 +1156,12 @@ uint16_t GCS_MAVLINK::get_reschedule_interval_ms(const deferred_message_bucket_t // we are sending requests for waypoints, penalize streams: interval_ms *= 4; } +#if AP_MAVLINK_FTP_ENABLED if (AP_HAL::millis() - ftp.last_send_ms < 500) { // we are sending ftp replies interval_ms *= 4; } +#endif if (interval_ms > 60000) { return 60000; @@ -4005,9 +4007,11 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg) break; #endif +#if AP_MAVLINK_FTP_ENABLED case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL: handle_file_transfer_protocol(msg); break; +#endif #if AP_CAMERA_ENABLED case MAVLINK_MSG_ID_DIGICAM_CONTROL: @@ -6771,10 +6775,12 @@ uint64_t GCS_MAVLINK::capabilities() const } #endif +#if AP_MAVLINK_FTP_ENABLED if (!AP_BoardConfig::ftp_disabled()){ //if ftp disable board option is not set ret |= MAV_PROTOCOL_CAPABILITY_FTP; } - +#endif + return ret; } diff --git a/libraries/GCS_MAVLink/GCS_FTP.cpp b/libraries/GCS_MAVLink/GCS_FTP.cpp index 3225688104b3b..10725ad586a23 100644 --- a/libraries/GCS_MAVLink/GCS_FTP.cpp +++ b/libraries/GCS_MAVLink/GCS_FTP.cpp @@ -17,7 +17,7 @@ #include "GCS_config.h" -#if HAL_GCS_ENABLED +#if AP_MAVLINK_FTP_ENABLED #include @@ -694,4 +694,4 @@ void GCS_MAVLINK::ftp_list_dir(struct pending_ftp &request, struct pending_ftp & AP::FS().closedir(dir); } -#endif // HAL_GCS_ENABLED +#endif // AP_MAVLINK_FTP_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 14449af38220f..64877c10649dd 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -84,6 +84,10 @@ #define AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED HAL_ADSB_ENABLED #endif +#ifndef AP_MAVLINK_FTP_ENABLED +#define AP_MAVLINK_FTP_ENABLED HAL_GCS_ENABLED +#endif + // GCS should be using MISSION_REQUEST_INT instead; this is a waste of // flash. MISSION_REQUEST was deprecated in June 2020. We started // sending warnings to the GCS in Sep 2022 if this command was used.