diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index da135b2d10..281cbe8a05 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -32,7 +32,7 @@ jobs: - name: Install dependencies run: sudo apt-get update && sudo apt-get install -y lcov python3-future - name: configure - run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Coverage -DASAN=ON -DWERROR=OFF -Bbuild -H. + run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Coverage -DASAN=ON -DWERROR=OFF -DENABLE_CPPTRACE=On -Bbuild -H. - name: build run: cmake --build build -j2 - name: unit tests @@ -64,13 +64,13 @@ jobs: cmake -Bthird_party/mavlink/build -Sthird_party/mavlink sudo cmake --build third_party/mavlink/build - name: configure - run: cmake -DCMAKE_BUILD_TYPE=Release -DSUPERBUILD=OFF -DWERROR=OFF -Bbuild/release -H. + run: cmake -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSUPERBUILD=OFF -DWERROR=OFF -DENABLE_CPPTRACE=On -Bbuild/release -H. - name: build run: cmake --build build/release -j2 - name: unit tests run: ./build/release/src/unit_tests/unit_tests_runner - - name: system tests - run: ./build/release/src/system_tests/system_tests_runner + #- name: system tests + # run: ./build/release/src/system_tests/system_tests_runner ubuntu-superbuild: name: ${{ matrix.ubuntu_image }} (mavsdk_server, superbuild) @@ -91,7 +91,7 @@ jobs: if: steps.cache.outputs.cache-hit == 'true' run: echo "superbuild=-DSUPERBUILD=OFF" >> $GITHUB_ENV && echo "cmake_prefix_path=-DCMAKE_PREFIX_PATH=$(pwd)/build/release/third_party/install" >> $GITHUB_ENV - name: configure - run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -DWERROR=OFF -Bbuild/release -H. + run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=RelWithDebInfo -DBUILD_MAVSDK_SERVER=ON -DWERROR=OFF -DENABLE_CPPTRACE=On -Bbuild/release -H. - name: build run: cmake --build build/release -j2 - name: install @@ -104,13 +104,13 @@ jobs: - name: install examples dependencies run: sudo apt-get install libsdl2-dev - name: configure examples - run: cmake -DCMAKE_PREFIX_PATH=$(pwd)/build/release/third_party/install -DCMAKE_BUILD_TYPE=Release -DWERROR=OFF -Bexamples/build -Hexamples + run: cmake -DCMAKE_PREFIX_PATH=$(pwd)/build/release/third_party/install -DCMAKE_BUILD_TYPE=RelWithDebInfo -DWERROR=OFF -Bexamples/build -Hexamples - name: build examples run: cmake --build examples/build -j2 - name: unit tests run: ./build/release/src/unit_tests/unit_tests_runner - - name: system tests - run: ./build/release/src/system_tests/system_tests_runner + # - name: system tests + # run: ./build/release/src/system_tests/system_tests_runner - name: test (mavsdk_server) run: ./build/release/src/mavsdk_server/test/unit_tests_mavsdk_server @@ -125,22 +125,22 @@ jobs: id: cache with: path: ~/.hunter - key: ${{ github.job }}-${{ hashFiles('~/.hunter/**') }} + key: ${{ github.job }}-${{ hashFiles('~/.hunter/**') }}-2 - name: install mavlink on the system run: | cmake -Bthird_party/mavlink/build -Sthird_party/mavlink sudo cmake --build third_party/mavlink/build - name: configure - run: cmake -DSUPERBUILD=OFF -DHUNTER_ENABLED=ON -DCMAKE_TOOLCHAIN_FILE=$(pwd)/src/cmake/fpic_toolchain.cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=OFF -DBUILD_SHARED_LIBS=OFF -Bbuild -H. + run: cmake -DSUPERBUILD=OFF -DHUNTER_ENABLED=ON -DCMAKE_TOOLCHAIN_FILE=$(pwd)/src/cmake/fpic_toolchain.cmake -DCMAKE_BUILD_TYPE=Debug -DBUILD_MAVSDK_SERVER=OFF -DBUILD_SHARED_LIBS=OFF -DENABLE_CPPTRACE=On -Bbuild -H. - name: build run: cmake --build build -j2 - name: unit tests run: ./build/src/unit_tests/unit_tests_runner - - name: system tests - run: ./build/src/system_tests/system_tests_runner + #- name: system tests + # run: ./build/src/system_tests/system_tests_runner - ubuntu20-proto-check: - name: ubuntu-22.04 (proto check) + ubuntu22-style-and-proto-check: + name: ubuntu-22.04 (style and proto check) runs-on: ubuntu-22.04 steps: - uses: actions/checkout@v3 @@ -157,7 +157,7 @@ jobs: if: steps.cache.outputs.cache-hit == 'true' run: echo "superbuild=-DSUPERBUILD=OFF" >> $GITHUB_ENV && echo "cmake_prefix_path=-DCMAKE_PREFIX_PATH=$(pwd)/build/default/third_party/install" >> $GITHUB_ENV - name: build necessary protoc tooling - run: cmake $superbuild $cmake_prefix_path -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -H. + run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Debug -DBUILD_MAVSDK_SERVER=ON -DENABLE_CPPTRACE=On -Bbuild/default -H. - name: generate code from protos run: PATH="$PATH:$HOME/.local/bin" tools/generate_from_protos.sh - name: fix style @@ -165,20 +165,6 @@ jobs: - name: check for diff run: git diff --exit-code - ubuntu20-check-style: - name: ubuntu-22.04 (check style and docs) - runs-on: ubuntu-20.04 - steps: - - uses: actions/checkout@v3 - with: - submodules: recursive - - name: install dependencies - run: sudo apt-get update && sudo apt-get install -y doxygen clang-format-12 - - name: check style - run: ./tools/fix_style.sh . - - name: check docs - run: tools/generate_docs.sh - deb-package: name: ${{ matrix.container_name }} (package, non-mavsdk_server) runs-on: ubuntu-20.04 @@ -195,7 +181,7 @@ jobs: git config --global --add safe.directory "$GITHUB_WORKSPACE" git config --global --add safe.directory /github/workspace - name: configure - run: cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=OFF -DBUILD_SHARED_LIBS=ON -DCMAKE_INSTALL_PREFIX=install -DWERROR=OFF -Bbuild/release -H. + run: cmake -DCMAKE_BUILD_TYPE=RelWithDebInfo -DBUILD_MAVSDK_SERVER=OFF -DBUILD_SHARED_LIBS=ON -DCMAKE_INSTALL_PREFIX=install -DWERROR=OFF -Bbuild/release -H. - name: build run: cmake --build build/release --target install -- -j2 - name: Package @@ -251,7 +237,7 @@ jobs: if: steps.cache.outputs.cache-hit == 'true' run: echo "superbuild=-DSUPERBUILD=OFF" >> $GITHUB_ENV && echo "cmake_prefix_path=-DCMAKE_PREFIX_PATH=/work/build/linux-${{ matrix.arch_name }}/third_party/install" >> $GITHUB_ENV - name: configure - run: ./dockcross-linux-${{ matrix.arch_name }}-custom /bin/bash -c "cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=build/linux-${{ matrix.arch_name }}/install -DBUILD_MAVSDK_SERVER=OFF -DBUILD_SHARED_LIBS=ON -DWERROR=OFF -Bbuild/linux-${{ matrix.arch_name }} -H." + run: ./dockcross-linux-${{ matrix.arch_name }}-custom /bin/bash -c "cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=build/linux-${{ matrix.arch_name }}/install -DBUILD_MAVSDK_SERVER=OFF -DBUILD_SHARED_LIBS=ON -DWERROR=OFF -Bbuild/linux-${{ matrix.arch_name }} -H." - name: build run: ./dockcross-linux-${{ matrix.arch_name }}-custom cmake --build build/linux-${{ matrix.arch_name }} -j2 --target install - name: create deb packages @@ -289,13 +275,13 @@ jobs: if: steps.cache.outputs.cache-hit == 'true' run: echo "superbuild=-DSUPERBUILD=OFF" >> $GITHUB_ENV && echo "cmake_prefix_path=-DCMAKE_PREFIX_PATH=$(pwd)/build/release/third_party/install" >> $GITHUB_ENV - name: configure - run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DBUILD_STATIC_MAVSDK_SERVER=ON -DCMAKE_INSTALL_PREFIX=install -DWERROR=OFF -Bbuild/release -H. + run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=RelWithDebInfo -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DBUILD_STATIC_MAVSDK_SERVER=ON -DCMAKE_INSTALL_PREFIX=install -DWERROR=OFF -DENABLE_CPPTRACE=On -Bbuild/release -H. - name: build run: cmake --build build/release --target install -- -j2 - name: unit tests run: ./build/release/src/unit_tests/unit_tests_runner - - name: system tests - run: ./build/release/src/system_tests/system_tests_runner + # - name: system tests + # run: ./build/release/src/system_tests/system_tests_runner - name: test (mavsdk_server) run: ./build/release/src/mavsdk_server/test/unit_tests_mavsdk_server - name: Upload as artefact @@ -335,7 +321,7 @@ jobs: if: steps.cache.outputs.cache-hit == 'true' run: echo "superbuild=-DSUPERBUILD=OFF" >> $GITHUB_ENV && echo "cmake_prefix_path=-DCMAKE_PREFIX_PATH=/work/build/${{ matrix.arch_name }}/third_party/install" >> $GITHUB_ENV - name: configure - run: ./dockcross-${{ matrix.arch_name }} /bin/bash -c "cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=build/${{ matrix.arch_name }}/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DBUILD_STATIC_MAVSDK_SERVER=ON -DWERROR=OFF -Bbuild/${{ matrix.arch_name }} -H." + run: ./dockcross-${{ matrix.arch_name }} /bin/bash -c "cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=build/${{ matrix.arch_name }}/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DBUILD_STATIC_MAVSDK_SERVER=ON -DWERROR=OFF -Bbuild/${{ matrix.arch_name }} -H." - name: build run: ./dockcross-${{ matrix.arch_name }} cmake --build build/${{ matrix.arch_name }} -j2 --target install - name: Publish artefacts @@ -377,7 +363,7 @@ jobs: if: steps.cache.outputs.cache-hit == 'true' run: echo "superbuild=-DSUPERBUILD=OFF" >> $GITHUB_ENV && echo "cmake_prefix_path=-DCMAKE_PREFIX_PATH=/work/build/${{ matrix.name }}/third_party/install" >> $GITHUB_ENV - name: configure - run: ./dockcross-${{ matrix.name }} /bin/bash -c "cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=build/${{ matrix.name }}/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DWERROR=OFF -Bbuild/${{ matrix.name }} -H." + run: ./dockcross-${{ matrix.name }} /bin/bash -c "cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=build/${{ matrix.name }}/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DWERROR=OFF -Bbuild/${{ matrix.name }} -H." - name: build run: ./dockcross-${{ matrix.name }} cmake --build build/${{ matrix.name }} -j2 --target install - name: create tar with header and library @@ -418,7 +404,7 @@ jobs: - name: set SDKROOT value run: echo "SDKROOT=$(xcrun --sdk macosx --show-sdk-path)" >> $GITHUB_ENV - name: configure - run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=build/macos/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DMACOS_FRAMEWORK=${{ matrix.build-framework }} -DWERROR=OFF -Bbuild/macos -H. + run: cmake $superbuild $cmake_prefix_path -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=build/macos/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DMACOS_FRAMEWORK=${{ matrix.build-framework }} -DWERROR=OFF -DENABLE_CPPTRACE=On -Bbuild/macos -H. - name: build run: cmake --build build/macos -j2 --target install - name: unit tests @@ -478,7 +464,7 @@ jobs: python3 -m pip install wheel python3 -m pip install future - name: configure - run: cmake $superbuild $cmake_prefix_path -DENABLE_STRICT_TRY_COMPILE=ON -DCMAKE_BUILD_TYPE=Release -DCMAKE_TOOLCHAIN_FILE=$(pwd)/tools/ios.toolchain.cmake -DENABLE_BITCODE=Off -DPLATFORM=${{ matrix.platform }} -DDEPLOYMENT_TARGET=14.0 -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DWERROR=OFF -Bbuild/${{ matrix.name }} -H. + run: cmake $superbuild $cmake_prefix_path -DENABLE_STRICT_TRY_COMPILE=ON -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_TOOLCHAIN_FILE=$(pwd)/tools/ios.toolchain.cmake -DENABLE_BITCODE=Off -DPLATFORM=${{ matrix.platform }} -DDEPLOYMENT_TARGET=14.0 -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DWERROR=OFF -Bbuild/${{ matrix.name }} -H. - name: build run: cmake --build build/${{ matrix.name }} -j2 - uses: actions/upload-artifact@v3 @@ -555,9 +541,9 @@ jobs: choco install nasm echo "C:\Program Files\NASM" | Out-File -FilePath $env:GITHUB_PATH -Encoding utf8 -Append - name: configure - run: cmake -G "Visual Studio 17 2022" $env:superbuild $env:cmake_prefix_path -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=build/release/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DWERROR=OFF -Bbuild/release -S. + run: cmake -G "Visual Studio 17 2022" $env:superbuild $env:cmake_prefix_path -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=build/release/install -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DWERROR=OFF -Bbuild/release -S. - name: build - run: cmake --build build/release -j2 --config Release --target install + run: cmake --build build/release -j2 --config RelWithDebInfo --target install - name: Create zip file mavsdk libraries if: startsWith(github.ref, 'refs/tags/v') run: cd build/release/install && 7z.exe a -tzip ../../../mavsdk-windows-x64-release.zip . && cd ../../.. diff --git a/examples/ftp_client/ftp_client.cpp b/examples/ftp_client/ftp_client.cpp index 8e4172c8f8..988d817008 100644 --- a/examples/ftp_client/ftp_client.cpp +++ b/examples/ftp_client/ftp_client.cpp @@ -47,14 +47,6 @@ void usage(const std::string& bin_name) << " 3 : Files are different (cmp command)\n"; } -Ftp::Result reset_server(Ftp& ftp) -{ - auto prom = std::promise{}; - auto future_result = prom.get_future(); - ftp.reset_async([&prom](Ftp::Result result) { prom.set_value(result); }); - return future_result.get(); -} - Ftp::Result create_directory(Ftp& ftp, const std::string& path) { std::cerr << "Creating directory: " << path << '\n'; @@ -131,7 +123,10 @@ download_file(Ftp& ftp, const std::string& remote_file_path, const std::string& auto prom = std::promise{}; auto future_result = prom.get_future(); ftp.download_async( - remote_file_path, local_path, [&prom](Ftp::Result result, Ftp::ProgressData progress) { + remote_file_path, + local_path, + false, + [&prom](Ftp::Result result, Ftp::ProgressData progress) { if (result == Ftp::Result::Next) { int percentage = progress.total_bytes > 0 ? progress.bytes_transferred * 100 / progress.total_bytes : @@ -215,13 +210,6 @@ int main(int argc, char** argv) return 1; } - Ftp::Result res; - res = reset_server(ftp); - if (res != Ftp::Result::Success) { - std::cerr << "Reset server error: " << res << '\n'; - return 1; - } - std::string command = argv[3]; if (command == "put") { @@ -229,7 +217,7 @@ int main(int argc, char** argv) usage(argv[0]); return 1; } - res = upload_file(ftp, argv[4], argv[5]); + auto res = upload_file(ftp, argv[4], argv[5]); if (res == Ftp::Result::Success) { std::cerr << "File uploaded.\n"; } else { @@ -241,7 +229,7 @@ int main(int argc, char** argv) usage(argv[0]); return 1; } - res = download_file(ftp, argv[4], (argc == 6) ? argv[5] : "."); + auto res = download_file(ftp, argv[4], (argc == 6) ? argv[5] : "."); if (res == Ftp::Result::Success) { std::cerr << "File downloaded.\n"; } else { @@ -253,7 +241,7 @@ int main(int argc, char** argv) usage(argv[0]); return 1; } - res = rename_file(ftp, argv[4], argv[5]); + auto res = rename_file(ftp, argv[4], argv[5]); if (res == Ftp::Result::Success) { std::cerr << "File renamed.\n"; } else { @@ -265,7 +253,7 @@ int main(int argc, char** argv) usage(argv[0]); return 1; } - res = create_directory(ftp, argv[4]); + auto res = create_directory(ftp, argv[4]); if (res == Ftp::Result::Success) { std::cerr << "Directory created.\n"; } else if (res == Ftp::Result::FileExists) { @@ -289,7 +277,7 @@ int main(int argc, char** argv) recursive = true; } } - res = remove_directory(ftp, path, recursive); + auto res = remove_directory(ftp, path, recursive); if (res == Ftp::Result::Success) { std::cerr << "Directory removed.\n"; } else if (res == Ftp::Result::FileDoesNotExist) { @@ -304,7 +292,7 @@ int main(int argc, char** argv) usage(argv[0]); return 1; } - res = list_directory(ftp, argv[4]); + auto res = list_directory(ftp, argv[4]); if (res == Ftp::Result::Success) { std::cerr << "Directory listed.\n"; } else if (res == Ftp::Result::FileDoesNotExist) { @@ -319,7 +307,7 @@ int main(int argc, char** argv) usage(argv[0]); return 1; } - res = remove_file(ftp, argv[4]); + auto res = remove_file(ftp, argv[4]); if (res == Ftp::Result::Success) { std::cerr << "File deleted.\n"; } else if (res == Ftp::Result::FileDoesNotExist) { diff --git a/examples/ftp_server/ftp_server.cpp b/examples/ftp_server/ftp_server.cpp index fc32a2779c..be2afabf05 100644 --- a/examples/ftp_server/ftp_server.cpp +++ b/examples/ftp_server/ftp_server.cpp @@ -3,7 +3,7 @@ // #include -#include +#include #include #include @@ -37,15 +37,15 @@ int main(int argc, char** argv) return 1; } - auto system_cc = mavsdk.systems().at(0); - - auto ftp_server = Ftp{system_cc}; - ftp_server.set_root_directory(argv[3]); + auto component = + mavsdk.server_component_by_type(mavsdk::Mavsdk::ServerComponentType::CompanionComputer); + auto ftp_server = FtpServer{component}; + ftp_server.set_root_dir(argv[3]); std::cout << "Mavlink FTP server running.\n" << '\n' << "Remote: " << argv[1] << ":" << argv[2] << '\n' - << "Component ID: " << static_cast(ftp_server.get_our_compid()) << '\n'; + << "Component ID: " << std::to_string(component->component_id()) << '\n'; while (true) { std::this_thread::sleep_for(std::chrono::seconds(1)); diff --git a/proto b/proto index 53df8f4571..84d4529d5a 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 53df8f4571bedbd15f3d4bc00f5176f8519b045f +Subproject commit 84d4529d5a69e96a52ec16a6a17f00e2d0476d65 diff --git a/src/integration_tests/CMakeLists.txt b/src/integration_tests/CMakeLists.txt index e8b5db2d76..94c83caebe 100644 --- a/src/integration_tests/CMakeLists.txt +++ b/src/integration_tests/CMakeLists.txt @@ -27,7 +27,6 @@ add_executable(integration_tests_runner offboard_attitude.cpp #logging.cpp # Not fully implemented log_files.cpp - ftp.cpp mission_cancellation.cpp mission_change_speed.cpp mission.cpp diff --git a/src/integration_tests/ftp.cpp b/src/integration_tests/ftp.cpp deleted file mode 100644 index fdf37bbcaf..0000000000 --- a/src/integration_tests/ftp.cpp +++ /dev/null @@ -1,350 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#include "integration_test_helper.h" -#include "mavsdk.h" -#include "system.h" -#include "plugins/ftp/ftp.h" - -#include -#include "plugins/mavlink_passthrough/mavlink_passthrough.h" -static std::default_random_engine random_engine; -static std::uniform_real_distribution<> distribution(0.0, 1.0); - -using namespace mavsdk; - -static std::atomic _bytes_transferred{0}; -static std::atomic _file_size{0}; - -void reset_server(std::shared_ptr& ftp) -{ - auto prom = std::make_shared>(); - auto future_result = prom->get_future(); - ftp->reset_async([prom](Ftp::Result result) { prom->set_value(result); }); - future_result.get(); -} - -void create_test_file(std::string file_name, uint32_t size) -{ - std::string str(size, 'X'); - std::ofstream of(file_name, std::fstream::trunc | std::fstream::binary); - of << str; - of.close(); -} - -void test_create_directory(std::shared_ptr ftp, const std::string& path) -{ - auto prom = std::make_shared>(); - auto future_result = prom->get_future(); - ftp->create_directory_async(path, [prom](Ftp::Result result) { prom->set_value(result); }); - - Ftp::Result result = future_result.get(); - EXPECT_TRUE( - result == Ftp::Result::Success || result == Ftp::Result::FileExists || - result == Ftp::Result::FileProtected); -} - -void test_list_directory(std::shared_ptr ftp, const std::string& path) -{ - auto prom = std::make_shared>>>(); - auto future_result = prom->get_future(); - ftp->list_directory_async(path, [prom](Ftp::Result result, std::vector list) { - prom->set_value(std::pair>(result, list)); - }); - - std::pair> result = future_result.get(); - EXPECT_EQ(result.first, Ftp::Result::Success); - EXPECT_GT(result.second.size(), 0); -} - -Ftp::Result test_remove_directory(std::shared_ptr ftp, const std::string& path) -{ - auto prom = std::make_shared>(); - auto future_result = prom->get_future(); - ftp->remove_directory_async(path, [prom](Ftp::Result result) { prom->set_value(result); }); - - return future_result.get(); -} - -Ftp::Result test_remove_file(std::shared_ptr ftp, const std::string& path) -{ - auto prom = std::make_shared>(); - auto future_result = prom->get_future(); - ftp->remove_file_async(path, [prom](Ftp::Result result) { prom->set_value(result); }); - - return future_result.get(); -} - -void test_download( - std::shared_ptr ftp, const std::string& remote_file, const std::string& local_path) -{ - auto prom = std::make_shared>(); - auto future_result = prom->get_future(); - - ftp->download_async( - remote_file, local_path, [prom](Ftp::Result result, Ftp::ProgressData progress) { - if (result == Ftp::Result::Next) { - int percentage = progress.bytes_transferred * 100 / progress.total_bytes; - std::cout << "\rDownloading [" << std::setw(3) << percentage << "%] " - << progress.bytes_transferred << " of " << progress.total_bytes; - if (progress.bytes_transferred >= progress.total_bytes) { - std::cout << '\n'; - } - _bytes_transferred = progress.bytes_transferred; - _file_size = progress.total_bytes; - } else { - prom->set_value(result); - } - }); - - Ftp::Result result = future_result.get(); - EXPECT_EQ(result, Ftp::Result::Success); - EXPECT_GT(_file_size, 0); - EXPECT_EQ(_bytes_transferred, _file_size); -} - -void test_upload( - std::shared_ptr ftp, const std::string& local_file, const std::string& remote_folder) -{ - auto prom = std::make_shared>(); - auto future_result = prom->get_future(); - _bytes_transferred = _file_size = 0; - ftp->upload_async( - local_file, remote_folder, [prom](Ftp::Result result, Ftp::ProgressData progress) { - if (result == Ftp::Result::Next) { - int percentage = progress.bytes_transferred * 100 / progress.total_bytes; - std::cout << "\rUploading " - << "[" << std::setw(3) << percentage << "%] " - << progress.bytes_transferred << " of " << progress.total_bytes; - if (progress.bytes_transferred == progress.total_bytes) { - std::cout << '\n'; - } - _bytes_transferred = progress.bytes_transferred; - _file_size = progress.total_bytes; - } else { - prom->set_value(result); - } - }); - - Ftp::Result result = future_result.get(); - EXPECT_GT(_file_size, 0); - EXPECT_EQ(_bytes_transferred, _file_size); - EXPECT_EQ(result, Ftp::Result::Success); -} - -void test_rename(std::shared_ptr ftp, const std::string& from, const std::string& to) -{ - auto prom = std::make_shared>(); - auto future_result = prom->get_future(); - ftp->rename_async(from, to, [prom](Ftp::Result result) { prom->set_value(result); }); - - Ftp::Result result = future_result.get(); - EXPECT_EQ(result, Ftp::Result::Success); -} - -void compare( - std::shared_ptr ftp, const std::string& local_file, const std::string& remote_file) -{ - auto prom = std::make_shared>>(); - auto future_result = prom->get_future(); - - ftp->are_files_identical_async( - local_file, remote_file, [&prom](Ftp::Result result, bool identical) { - prom->set_value(std::make_pair<>(result, identical)); - }); - - auto result = future_result.get(); - EXPECT_EQ(result.first, Ftp::Result::Success); - EXPECT_EQ(result.second, true); -} - -TEST(FtpTest, ListDirectory) -{ - Mavsdk mavsdk; - - ConnectionResult ret = mavsdk.add_udp_connection(); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - ASSERT_EQ(mavsdk.systems().size(), 1); - auto system = mavsdk.systems().at(0); - auto ftp = std::make_shared(system); - - // Reset server in case there are stale open sessions - reset_server(ftp); - - test_list_directory(ftp, "/"); -} - -TEST(FtpTest, DownloadFile) -{ - Mavsdk mavsdk; - - ConnectionResult ret = mavsdk.add_udp_connection(); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - ASSERT_EQ(mavsdk.systems().size(), 1); - auto system = mavsdk.systems().at(0); - auto ftp = std::make_shared(system); - - // Reset server in case there are stale open sessions - reset_server(ftp); - - auto mavlink_passthrough = std::make_shared(system); - mavsdk.intercept_incoming_messages_async([](const mavlink_message_t& message) { - if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - return true; - } - return (distribution(random_engine) > 0.01); - }); - mavsdk.intercept_outgoing_messages_async([](const mavlink_message_t& message) { - if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - return true; - } - return (distribution(random_engine) > 0.01); - }); - - test_download(ftp, "/dataman", "."); - remove("dataman"); -} - -TEST(FtpTest, UploadFiles) -{ - Mavsdk mavsdk; - - ConnectionResult ret = mavsdk.add_udp_connection(); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - ASSERT_EQ(mavsdk.systems().size(), 1); - auto system = mavsdk.systems().at(0); - auto ftp = std::make_shared(system); - - // Reset server in case there are stale open sessions - reset_server(ftp); - - auto mavlink_passthrough = std::make_shared(system); - mavsdk.intercept_incoming_messages_async([](const mavlink_message_t& message) { - if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - return true; - } - return (distribution(random_engine) > 0.01); - }); - mavsdk.intercept_outgoing_messages_async([](const mavlink_message_t& message) { - if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - return true; - } - return (distribution(random_engine) > 0.1); - }); - - test_create_directory(ftp, "/test"); - - const int number_of_files = 100; - for (int i = 0; i < number_of_files; i++) { - std::string file_name = "test_file_" + std::to_string(i); - create_test_file(file_name, 1024); - test_upload(ftp, file_name, "/test"); - compare(ftp, file_name, "/test/" + file_name); - remove(file_name.c_str()); - } - - { - auto prom = - std::make_shared>>>(); - auto future_result = prom->get_future(); - ftp->list_directory_async( - "/test", [prom](Ftp::Result result, std::vector list) { - prom->set_value(std::pair>(result, list)); - }); - - std::pair> result = future_result.get(); - int count = 0; - for (auto entry : result.second) { - if (entry.rfind("Ftest_file_", 0) == 0) { - count++; - } - } - EXPECT_EQ(result.first, Ftp::Result::Success); - EXPECT_GT(result.second.size(), 0); - EXPECT_EQ(count, number_of_files); - } -} - -TEST(FtpTest, TestServer) -{ - Mavsdk mavsdk_gcs; - Mavsdk::Configuration config_gcs(Mavsdk::Configuration::UsageType::GroundStation); - mavsdk_gcs.set_configuration(config_gcs); - ASSERT_EQ(mavsdk_gcs.add_any_connection("udp://:24550"), ConnectionResult::Success); - - Mavsdk mavsdk_cc; - Mavsdk::Configuration config_cc(Mavsdk::Configuration::UsageType::GroundStation); - mavsdk_cc.set_configuration(config_cc); - ASSERT_EQ(mavsdk_cc.add_any_connection("udp://127.0.0.1:24550"), ConnectionResult::Success); - - std::this_thread::sleep_for(std::chrono::seconds(1)); - - auto system_gcs = mavsdk_gcs.systems().at(0); - auto system_cc = mavsdk_cc.systems().at(0); - - auto mavlink_passthrough_cc = std::make_shared(system_cc); - mavsdk_cc.intercept_incoming_messages_async([](const mavlink_message_t& message) { - if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - return true; - } - return (distribution(random_engine) > 0.1); - }); - mavsdk_cc.intercept_outgoing_messages_async([](const mavlink_message_t& message) { - if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - return true; - } - return (distribution(random_engine) > 0.1); - }); - - auto ftp_server = std::make_shared(system_cc); - ftp_server->set_root_directory("."); - uint8_t server_comp_id = ftp_server->get_our_compid(); - - auto ftp_client = std::make_shared(system_gcs); - ftp_client->set_target_compid(server_comp_id); - - test_list_directory(ftp_client, "/"); - - ftp_server->set_root_directory("."); - test_create_directory(ftp_client, "test"); - - std::string file_name1 = "ftp_data_file1"; - std::string file_name2 = "ftp_data_file2"; - create_test_file(file_name1, 100000); - - test_upload(ftp_client, file_name1, "test"); - - compare(ftp_client, file_name1, "test/" + file_name1); - - test_rename(ftp_client, "test/" + file_name1, "test/" + file_name2); - - compare(ftp_client, file_name1, "test/" + file_name2); - - test_download(ftp_client, "test/" + file_name2, "."); - - Ftp::Result result = test_remove_file(ftp_client, "test/" + file_name1); - EXPECT_EQ(result, Ftp::Result::FileDoesNotExist); - - result = test_remove_file(ftp_client, "test/" + file_name2); - EXPECT_EQ(result, Ftp::Result::Success); - - result = test_remove_directory(ftp_client, "test"); - EXPECT_EQ(result, Ftp::Result::Success); -} diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index 630e0c6859..efe8a8abe0 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -22,14 +22,14 @@ target_sources(mavsdk system.cpp system_impl.cpp flight_mode.cpp - fs.cpp mavsdk.cpp mavsdk_impl.cpp http_loader.cpp mavlink_channels.cpp mavlink_command_receiver.cpp mavlink_command_sender.cpp - mavlink_ftp.cpp + mavlink_ftp_client.cpp + mavlink_ftp_server.cpp mavlink_mission_transfer.cpp mavlink_parameter_cache.cpp mavlink_parameter_client.cpp @@ -147,7 +147,6 @@ list(APPEND UNIT_TEST_SOURCES ${PROJECT_SOURCE_DIR}/mavsdk/core/cli_arg_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/curl_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/locked_queue_test.cpp - ${PROJECT_SOURCE_DIR}/mavsdk/core/fs_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/geometry_test.cpp # TODO: add this again #${PROJECT_SOURCE_DIR}/mavsdk/core/http_loader_test.cpp diff --git a/src/mavsdk/core/filesystem_include.h b/src/mavsdk/core/filesystem_include.h deleted file mode 100644 index 1d989c5732..0000000000 --- a/src/mavsdk/core/filesystem_include.h +++ /dev/null @@ -1,11 +0,0 @@ -#pragma once - -#if __has_include() -#include -namespace fs = std::filesystem; -#elif __has_include() -#include -namespace fs = std::experimental::filesystem; -#else -#error "Missing the header." -#endif diff --git a/src/mavsdk/core/fs.cpp b/src/mavsdk/core/fs.cpp deleted file mode 100644 index dfd2184508..0000000000 --- a/src/mavsdk/core/fs.cpp +++ /dev/null @@ -1,154 +0,0 @@ -#if defined(WINDOWS) -#include "tronkko_dirent.h" -#include "stackoverflow_unistd.h" -#include -#define mkdir(D, M) _mkdir(D) -#else -#include -#include -#endif - -#include -#include -#include -#include -#include - -#include "fs.h" -#include "filesystem_include.h" -#include "log.h" - -#ifndef PATH_MAX -#define PATH_MAX 4096 -#endif - -#include - -namespace mavsdk { - -bool fs_exists(const std::string& filename) -{ - struct stat buffer; - return (stat(filename.c_str(), &buffer) == 0); -} - -uint32_t fs_file_size(const std::string& filename) -{ - struct stat stat_buf; - int rc = stat(filename.c_str(), &stat_buf); - return (rc == 0) ? stat_buf.st_size : 0; -} - -static void relative_dir_base_split(const std::string& path, std::string& dir, std::string& base) -{ - std::string::size_type slash_pos = path.rfind(path_separator); - if (slash_pos != std::string::npos) { - slash_pos++; - dir = path.substr(0, slash_pos); - base = path.substr(slash_pos); - } else { - dir.clear(); - base = path; - } -} - -std::string fs_filename(const std::string& path) -{ - std::string dir; - std::string base; - relative_dir_base_split(path, dir, base); - return base; -} - -std::string fs_canonical(const std::string& path) -{ - std::deque st; - std::string res; - - int len = path.length(); - - int index = 0; - while (index < len) { - int next_index = path.find(path_separator, index); - if (next_index == -1) { - next_index = path.size(); - } - - std::string dir = path.substr(index, next_index - index); - - if (dir.compare("..") == 0 && !st.empty()) { - st.pop_back(); - } else if (dir.length() != 0 && dir.compare(".") != 0) { - st.push_back(dir); - } - - index = next_index + path_separator.size(); - } - - if (path.rfind(path_separator, path_separator.size() - 1) != 0) { - char buffer[PATH_MAX]; - if (getcwd(buffer, sizeof(buffer)) != nullptr) { - res.append(buffer); - if (!st.empty()) { - res.append(path_separator); - } - } - } else { - res.append(path_separator); - } - - while (!st.empty()) { - std::string temp = st.front(); - if (st.size() != 1) { - res.append(temp + path_separator); - } else { - res.append(temp); - } - st.pop_front(); - } - - return res; -} - -bool fs_create_directory(const std::string& path) -{ - return (mkdir(path.c_str(), (S_IRWXU | S_IRWXG | S_IRWXO)) == 0); -} - -bool fs_remove(const std::string& path) -{ - return (remove(path.c_str()) == 0); -} - -bool fs_rename(const std::string& old_name, const std::string& new_name) -{ - return (rename(old_name.c_str(), new_name.c_str()) == 0); -} - -// Inspired by https://stackoverflow.com/a/58454949/8548472 -std::optional create_tmp_directory(const std::string& prefix) -{ - const auto tmp_dir = fs::temp_directory_path(); - - std::random_device dev; - std::mt19937 prng(dev()); - std::uniform_int_distribution rand(0); - - static constexpr unsigned max_tries = 100; - - for (unsigned i = 0; i < max_tries; ++i) { - std::stringstream ss; - ss << prefix << '-' << std::hex << rand(prng); - auto path = tmp_dir / ss.str(); - - const auto created = fs::create_directory(path); - if (created) { - return {path.string()}; - } - } - - LogErr() << "Could not create a temporary directory, aborting."; - return {}; -} - -} // namespace mavsdk diff --git a/src/mavsdk/core/fs.h b/src/mavsdk/core/fs.h deleted file mode 100644 index 3ceafbc7df..0000000000 --- a/src/mavsdk/core/fs.h +++ /dev/null @@ -1,31 +0,0 @@ -#pragma once - -#include -#include -#include - -namespace mavsdk { - -#if defined(WINDOWS) -const std::string path_separator = "\\"; -#else -const std::string path_separator = "/"; -#endif - -bool fs_exists(const std::string& filename); - -uint32_t fs_file_size(const std::string& filename); - -std::string fs_filename(const std::string& path); - -std::string fs_canonical(const std::string& path); - -bool fs_create_directory(const std::string& path); - -bool fs_remove(const std::string& path); - -bool fs_rename(const std::string& old_name, const std::string& new_name); - -std::optional create_tmp_directory(const std::string& prefix); - -} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/core/fs_test.cpp b/src/mavsdk/core/fs_test.cpp deleted file mode 100644 index c6b11e97d2..0000000000 --- a/src/mavsdk/core/fs_test.cpp +++ /dev/null @@ -1,82 +0,0 @@ -#include - -#include "fs.h" -#include "unused.h" - -#if !defined(WINDOWS) -#define PATH_MAX 4096 - -#include - -TEST(Filesystem, AbsolutePathUnchanged) -{ - const std::string path = "/sbin/init"; - ASSERT_EQ(path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, RemoveFinalSlash) -{ - const std::string path = "/usr/local/include/mavsdk/"; - const std::string canonical_path = "/usr/local/include/mavsdk"; - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, RemoveDuplicateSlashes) -{ - const std::string path = "//////opt/////ros////foxy"; - const std::string canonical_path = "/opt/ros/foxy"; - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, RemoveInternalDots) -{ - const std::string path = "/sys/./class/./input"; - const std::string canonical_path = "/sys/class/input"; - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, ResolveDoubleDots) -{ - const std::string path = "/bin/../dev/../etc/crontab/../shadow"; - const std::string canonical_path = "/etc/shadow"; - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, RelativePathEmpty) -{ - char cwd[PATH_MAX]; - UNUSED(getcwd(cwd, PATH_MAX)); - const std::string path = ""; - const std::string canonical_path = std::string(cwd); - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, RelativePathDot) -{ - char cwd[PATH_MAX]; - UNUSED(getcwd(cwd, PATH_MAX)); - const std::string path = "."; - const std::string canonical_path = std::string(cwd); - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, RelativePathBare) -{ - char cwd[PATH_MAX]; - UNUSED(getcwd(cwd, PATH_MAX)); - const std::string path = "src/mavsdk/core/fs_test.cpp"; - const std::string canonical_path = std::string(cwd) + mavsdk::path_separator + path; - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(path)); -} - -TEST(Filesystem, RelativePathDotSlash) -{ - char cwd[PATH_MAX]; - UNUSED(getcwd(cwd, PATH_MAX)); - const std::string bare_path = "src/mavsdk/plugins/mavlink_passthrough"; - const std::string dotslash_path = "./" + bare_path; - const std::string canonical_path = std::string(cwd) + mavsdk::path_separator + bare_path; - ASSERT_EQ(canonical_path, mavsdk::fs_canonical(dotslash_path)); -} - -#endif diff --git a/src/mavsdk/core/include/mavsdk/server_component.h b/src/mavsdk/core/include/mavsdk/server_component.h index 67e71ceac5..e205cefdd9 100644 --- a/src/mavsdk/core/include/mavsdk/server_component.h +++ b/src/mavsdk/core/include/mavsdk/server_component.h @@ -26,6 +26,11 @@ class ServerComponent { */ ~ServerComponent() = default; + /** + * @brief MAVLink component ID of this component + */ + uint8_t component_id() const; + private: std::shared_ptr _impl; diff --git a/src/mavsdk/core/mavlink_ftp.cpp b/src/mavsdk/core/mavlink_ftp.cpp deleted file mode 100644 index e45808deb6..0000000000 --- a/src/mavsdk/core/mavlink_ftp.cpp +++ /dev/null @@ -1,1429 +0,0 @@ -#include "mavlink_ftp.h" -#include "system_impl.h" -#include - -#if defined(WINDOWS) -#include "tronkko_dirent.h" -#include "stackoverflow_unistd.h" -#else -#include -#include -#endif -#include -#include - -#ifndef O_ACCMODE -#define O_ACCMODE (O_RDONLY | O_WRONLY | O_RDWR) -#endif - -#include "crc32.h" -#include "fs.h" -#include - -namespace mavsdk { - -bool seq_lt(uint16_t a, uint16_t b) -{ - // From https://en.wikipedia.org/wiki/Serial_number_arithmetic - return (a < b && (b - a) < (std::numeric_limits::max() / 2)) || - (a > b && (a - b) > (std::numeric_limits::max() / 2)); -} - -MavlinkFtp::MavlinkFtp(SystemImpl& system_impl) : _system_impl(system_impl) -{ - _system_impl.register_mavlink_message_handler( - MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, - [this](const mavlink_message_t& message) { process_mavlink_ftp_message(message); }, - this); -} - -void MavlinkFtp::process_mavlink_ftp_message(const mavlink_message_t& msg) -{ - if (msg.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - return; - } - - bool stream_send = false; - mavlink_file_transfer_protocol_t ftp_req; - mavlink_msg_file_transfer_protocol_decode(&msg, &ftp_req); - - if (ftp_req.target_component != 0 && ftp_req.target_component != get_our_compid()) { - LogWarn() << "wrong compid!"; - return; - } - - PayloadHeader* payload = reinterpret_cast(&ftp_req.payload[0]); - - ServerResult error_code = ServerResult::SUCCESS; - - // basic sanity checks; must validate length before use - if (payload->size > max_data_length) { - error_code = ServerResult::ERR_INVALID_DATA_SIZE; - } else { - /* - LogDebug() << "ftp - opc: " << (int)payload->opcode << " size: " - << (int)payload->size << " offset: " << (int)payload->offset << " seq: " << - payload->seq_number; - */ - - // check the sequence number: if this is a resent request, resend the last response - if (_last_reply_valid) { - if (payload->seq_number + 1 == _last_reply_seq) { - // This is the same request as the one we replied to last. - LogWarn() << "Wrong sequence - resend last response"; - _system_impl.send_message(_last_reply); - return; - } - } - - switch (payload->opcode) { - case CMD_NONE: - LogInfo() << "OPC:CMD_NONE"; - break; - - case CMD_TERMINATE_SESSION: - LogInfo() << "OPC:CMD_TERMINATE_SESSION"; - error_code = _work_terminate(payload); - break; - - case CMD_RESET_SESSIONS: - LogInfo() << "OPC:CMD_RESET_SESSIONS"; - error_code = _work_reset(payload); - break; - - case CMD_LIST_DIRECTORY: - LogInfo() << "OPC:CMD_LIST_DIRECTORY"; - error_code = _work_list(payload); - break; - - case CMD_OPEN_FILE_RO: - LogInfo() << "OPC:CMD_OPEN_FILE_RO"; - error_code = _work_open(payload, O_RDONLY); - break; - - case CMD_CREATE_FILE: - LogInfo() << "OPC:CMD_CREATE_FILE"; - error_code = _work_open(payload, O_CREAT | O_TRUNC | O_WRONLY); - break; - - case CMD_OPEN_FILE_WO: - LogInfo() << "OPC:CMD_OPEN_FILE_WO"; - error_code = _work_open(payload, O_CREAT | O_WRONLY); - break; - - case CMD_READ_FILE: - LogInfo() << "OPC:CMD_READ_FILE"; - error_code = _work_read(payload); - break; - - case CMD_BURST_READ_FILE: - LogInfo() << "OPC:CMD_BURST_READ_FILE"; - error_code = _work_burst(payload); - stream_send = true; - break; - - case CMD_WRITE_FILE: - LogInfo() << "OPC:CMD_WRITE_FILE"; - error_code = _work_write(payload); - break; - - case CMD_REMOVE_FILE: - LogInfo() << "OPC:CMD_REMOVE_FILE"; - error_code = _work_remove_file(payload); - break; - - case CMD_RENAME: - LogInfo() << "OPC:CMD_RENAME"; - error_code = _work_rename(payload); - break; - - case CMD_CREATE_DIRECTORY: - LogInfo() << "OPC:CMD_CREATE_DIRECTORY"; - error_code = _work_create_directory(payload); - break; - - case CMD_REMOVE_DIRECTORY: - LogInfo() << "OPC:CMD_REMOVE_DIRECTORY"; - error_code = _work_remove_directory(payload); - break; - - case CMD_CALC_FILE_CRC32: - LogInfo() << "OPC:CMD_CALC_FILE_CRC32"; - error_code = _work_calc_file_CRC32(payload); - break; - - case RSP_ACK: - _process_ack(payload); - return; - - case RSP_NAK: - _process_nak(payload); - return; - - default: - LogWarn() << "OPC:Unknown command: " << static_cast(payload->opcode); - error_code = ServerResult::ERR_UNKOWN_COMMAND; - break; - } - } - - payload->seq_number++; - - // handle success vs. error - if (error_code == ServerResult::SUCCESS) { - payload->req_opcode = payload->opcode; - payload->opcode = RSP_ACK; - - } else { - uint8_t r_errno = errno; - payload->req_opcode = payload->opcode; - payload->opcode = RSP_NAK; - payload->size = 1; - - if (r_errno == EEXIST) { - error_code = ServerResult::ERR_FAIL_FILE_EXISTS; - } else if (r_errno == ENOENT && error_code == ServerResult::ERR_FAIL_ERRNO) { - error_code = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - - *reinterpret_cast(payload->data) = error_code; - - if (error_code == ServerResult::ERR_FAIL_ERRNO) { - payload->size = 2; - *reinterpret_cast(payload->data + 1) = r_errno; - } - } - - _last_reply_valid = false; - - // Stream download replies are sent through mavlink stream mechanism. Unless we need to Nack. - if (!stream_send || error_code != ServerResult::SUCCESS) { - // keep a copy of the last sent response ((n)ack), so that if it gets lost and the GCS - // resends the request, we can simply resend the response. - _last_reply_valid = true; - _last_reply_seq = payload->seq_number; - mavlink_msg_file_transfer_protocol_pack( - _system_impl.get_own_system_id(), - _system_impl.get_own_component_id(), - &_last_reply, - _network_id, - _system_impl.get_system_id(), - _get_target_component_id(), - reinterpret_cast(payload)); - _system_impl.send_message(_last_reply); - } -} - -MavlinkFtp::~MavlinkFtp() {} - -void MavlinkFtp::_process_ack(PayloadHeader* payload) -{ - std::lock_guard lock(_curr_op_mutex); - - if (seq_lt(payload->seq_number, _seq_number)) { - // (payload->seq_number < _seq_number) with wrap around - // received an ack for a previous seq that we already considered done - return; - } - - if (_curr_op != payload->req_opcode) { - LogWarn() << "Received ACK not matching our current operation"; - return; - } - - switch (_curr_op) { - case CMD_NONE: - LogWarn() << "Received ACK without active operation"; - break; - - case CMD_OPEN_FILE_RO: - _curr_op = CMD_NONE; - _session_valid = true; - _session = payload->session; - _bytes_transferred = 0; - _file_size = *(reinterpret_cast(payload->data)); - _call_op_progress_callback(_bytes_transferred, _file_size); - _read(); - break; - - case CMD_READ_FILE: - _ofstream.stream.write(reinterpret_cast(payload->data), payload->size); - if (!_ofstream.stream) { - _session_result = ServerResult::ERR_FILE_IO_ERROR; - _end_read_session(); - return; - } - _bytes_transferred += payload->size; - _call_op_progress_callback(_bytes_transferred, _file_size); - _read(); - break; - - case CMD_OPEN_FILE_WO: - _curr_op = CMD_NONE; - _session_valid = true; - _session = payload->session; - _bytes_transferred = 0; - _call_op_progress_callback(_bytes_transferred, _file_size); - _write(); - break; - - case CMD_WRITE_FILE: - _call_op_progress_callback(_bytes_transferred, _file_size); - _write(); - break; - - case CMD_TERMINATE_SESSION: - _curr_op = CMD_NONE; - _session_valid = false; - _stop_timer(); - _call_op_result_callback(_session_result); - break; - - case CMD_RESET_SESSIONS: - _curr_op = CMD_NONE; - _session_valid = false; - _stop_timer(); - _call_op_result_callback(_session_result); - break; - - case CMD_LIST_DIRECTORY: { - bool added = false; - uint8_t start = 0; - for (uint8_t i = 0; i < payload->size; i++) { - if (payload->data[i] == 0) { - std::string entry = std::string(reinterpret_cast(&payload->data[start])); - if (entry.length() > 0) { - added = true; - _curr_directory_list.emplace_back(entry); - } - start = i + 1; - } - } - if (added) { - // Ask for next batch of file names - _list_directory(_curr_directory_list.size()); - } else { - // We came to end - report entire list - _curr_op = CMD_NONE; - _stop_timer(); - _call_dir_items_result_callback(ServerResult::SUCCESS, _curr_directory_list); - } - break; - } - - case CMD_CALC_FILE_CRC32: { - _curr_op = CMD_NONE; - uint32_t checksum = *reinterpret_cast(payload->data); - _stop_timer(); - _call_crc32_result_callback(ServerResult::SUCCESS, checksum); - break; - } - - default: - _curr_op = CMD_NONE; - _stop_timer(); - _call_op_result_callback(ServerResult::SUCCESS); - break; - } -} - -void MavlinkFtp::_process_nak(PayloadHeader* payload) -{ - if (payload != nullptr) { - ServerResult sr = static_cast(payload->data[0]); - // PX4 Mavlink FTP returns "File doesn't exist" this way - if (sr == ServerResult::ERR_FAIL_ERRNO && payload->data[1] == ENOENT) { - sr = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - _process_nak(sr); - } -} - -void MavlinkFtp::_process_nak(ServerResult result) -{ - std::lock_guard lock(_curr_op_mutex); - switch (_curr_op) { - case CMD_NONE: - LogWarn() << "Received NAK without active operation"; - break; - - case CMD_OPEN_FILE_RO: - case CMD_READ_FILE: - _session_result = result; - if (_session_valid) { - const bool delete_file = (result == ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST); - _end_read_session(delete_file); - } else { - _stop_timer(); - _call_op_result_callback(_session_result); - } - break; - - case CMD_OPEN_FILE_WO: - case CMD_WRITE_FILE: - _session_result = result; - if (_session_valid) { - _end_write_session(); - } else { - _stop_timer(); - _call_op_result_callback(_session_result); - } - break; - - case CMD_TERMINATE_SESSION: - _session_valid = false; - _stop_timer(); - _call_op_result_callback(_session_result); - break; - - case CMD_LIST_DIRECTORY: - _stop_timer(); - if (!_curr_directory_list.empty()) { - _call_dir_items_result_callback(ServerResult::SUCCESS, _curr_directory_list); - } else { - _call_dir_items_result_callback(result, _curr_directory_list); - } - break; - - case CMD_CALC_FILE_CRC32: - _stop_timer(); - _call_crc32_result_callback(result, 0); - break; - - default: - _stop_timer(); - _call_op_result_callback(result); - break; - } - _curr_op = CMD_NONE; -} - -void MavlinkFtp::_call_op_result_callback(ServerResult result) -{ - if (_curr_op_result_callback) { - const auto temp_callback = _curr_op_result_callback; - _system_impl.call_user_callback( - [temp_callback, result]() { temp_callback(_translate(result)); }); - } -} - -void MavlinkFtp::_call_op_progress_callback(uint32_t bytes_read, uint32_t total_bytes) -{ - if (_curr_op_progress_callback) { - // Slow callback down to only report ever 1%, otherwise we are slowing - // everything down way too much. - int percentage = 100 * bytes_read / total_bytes; - if (_last_progress_percentage != percentage) { - _last_progress_percentage = percentage; - - const auto temp_callback = _curr_op_progress_callback; - _system_impl.call_user_callback([temp_callback, bytes_read, total_bytes]() { - ProgressData progress; - progress.bytes_transferred = bytes_read; - progress.total_bytes = total_bytes; - temp_callback(ClientResult::Next, progress); - }); - } - } -} - -void MavlinkFtp::_call_dir_items_result_callback(ServerResult result, std::vector list) -{ - if (_curr_dir_items_result_callback) { - const auto temp_callback = _curr_dir_items_result_callback; - _system_impl.call_user_callback( - [temp_callback, result, list]() { temp_callback(_translate(result), list); }); - } -} - -void MavlinkFtp::_call_crc32_result_callback(ServerResult result, uint32_t crc32) -{ - if (_current_crc32_result_callback) { - const auto temp_callback = _current_crc32_result_callback; - _system_impl.call_user_callback( - [temp_callback, result, crc32]() { temp_callback(_translate(result), crc32); }); - } -} - -MavlinkFtp::ClientResult MavlinkFtp::_translate(ServerResult result) -{ - switch (result) { - case ServerResult::SUCCESS: - return ClientResult::Success; - case ServerResult::ERR_TIMEOUT: - return ClientResult::Timeout; - case ServerResult::ERR_FILE_IO_ERROR: - return ClientResult::FileIoError; - case ServerResult::ERR_FAIL_FILE_EXISTS: - return ClientResult::FileExists; - case ServerResult::ERR_FAIL_FILE_PROTECTED: - return ClientResult::FileProtected; - case ServerResult::ERR_UNKOWN_COMMAND: - return ClientResult::Unsupported; - case ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST: - return ClientResult::FileDoesNotExist; - default: - return ClientResult::ProtocolError; - } -} - -void MavlinkFtp::reset_async(ResultCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - if (_curr_op != CMD_NONE) { - callback(ClientResult::Busy); - return; - } - - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = _session; - payload.opcode = _curr_op = CMD_RESET_SESSIONS; - payload.offset = 0; - payload.size = 0; - _curr_op_result_callback = callback; - _send_mavlink_ftp_message(payload); -} - -void MavlinkFtp::download_async( - const std::string& remote_path, const std::string& local_folder, DownloadCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - if (_curr_op != CMD_NONE) { - ProgressData empty{}; - callback(ClientResult::Busy, empty); - return; - } - - std::string local_path = local_folder + path_separator + fs_filename(remote_path); - - _ofstream.stream.open(local_path, std::fstream::trunc | std::fstream::binary); - _ofstream.path = local_path; - if (!_ofstream.stream) { - _end_read_session(); - ProgressData empty{}; - callback(ClientResult::FileIoError, empty); - return; - } - - _curr_op_progress_callback = callback; - _last_progress_percentage = -1; - - const auto result_callback = [callback](ClientResult result) { - ProgressData empty{}; - callback(result, empty); - }; - - _generic_command_async(CMD_OPEN_FILE_RO, 0, remote_path, result_callback); -} - -void MavlinkFtp::_end_read_session(bool delete_file) -{ - _curr_op = CMD_NONE; - if (_ofstream.stream.is_open()) { - _ofstream.stream.close(); - - if (delete_file) { - fs_remove(_ofstream.path); - } - } - _terminate_session(); -} - -void MavlinkFtp::_read() -{ - if (_bytes_transferred >= _file_size) { - _session_result = ServerResult::SUCCESS; - _end_read_session(); - return; - } - - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = _session; - payload.opcode = _curr_op = CMD_READ_FILE; - payload.offset = _bytes_transferred; - payload.size = - std::min(static_cast(max_data_length), _file_size - _bytes_transferred); - _send_mavlink_ftp_message(payload); -} - -void MavlinkFtp::upload_async( - const std::string& local_file_path, const std::string& remote_folder, UploadCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - if (_curr_op != CMD_NONE) { - ProgressData empty{}; - callback(ClientResult::Busy, empty); - return; - } - - if (!fs_exists(local_file_path)) { - ProgressData empty{}; - callback(ClientResult::FileDoesNotExist, empty); - return; - } - - _ifstream.open(local_file_path, std::fstream::binary); - if (!_ifstream) { - _end_write_session(); - ProgressData empty{}; - callback(ClientResult::FileIoError, empty); - return; - } - - _file_size = fs_file_size(local_file_path); - _curr_op_progress_callback = callback; - _last_progress_percentage = -1; - - std::string local_path(local_file_path); - std::string remote_file_path = remote_folder + path_separator + fs_filename(local_path); - - const auto result_callback = [callback](ClientResult result) { - ProgressData empty{}; - callback(result, empty); - }; - - _generic_command_async(CMD_OPEN_FILE_WO, 0, remote_file_path, result_callback); -} - -void MavlinkFtp::_end_write_session() -{ - _curr_op = CMD_NONE; - if (_ifstream) { - _ifstream.close(); - } - _terminate_session(); -} - -void MavlinkFtp::_write() -{ - if (_bytes_transferred >= _file_size) { - _session_result = ServerResult::SUCCESS; - _end_write_session(); - return; - } - - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = _session; - payload.opcode = _curr_op = CMD_WRITE_FILE; - payload.offset = _bytes_transferred; - int bytes_read = _ifstream.readsome(reinterpret_cast(payload.data), max_data_length); - if (!_ifstream) { - _end_write_session(); - _call_op_result_callback(ServerResult::ERR_FILE_IO_ERROR); - return; - } - payload.size = bytes_read; - _bytes_transferred += bytes_read; - _send_mavlink_ftp_message(payload); -} - -void MavlinkFtp::_terminate_session() -{ - if (!_session_valid) { - return; - } - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = _session; - payload.opcode = _curr_op = CMD_TERMINATE_SESSION; - payload.offset = 0; - payload.size = 0; - _send_mavlink_ftp_message(payload); -} - -std::pair> -MavlinkFtp::list_directory(const std::string& path) -{ - std::promise>> prom; - auto fut = prom.get_future(); - - list_directory_async( - path, [&prom](const ClientResult result, const std::vector dirs) { - prom.set_value(std::make_pair(result, dirs)); - }); - - return fut.get(); -} - -void MavlinkFtp::list_directory_async( - const std::string& path, ListDirectoryCallback callback, uint32_t offset) -{ - std::lock_guard lock(_curr_op_mutex); - if (_curr_op != CMD_NONE && offset == 0) { - callback(ClientResult::Busy, std::vector()); - return; - } - if (path.length() >= max_data_length) { - callback(ClientResult::InvalidParameter, std::vector()); - return; - } - - _last_path = path; - // TODOTODO - _curr_dir_items_result_callback = callback; - _list_directory(offset); -} - -void MavlinkFtp::_list_directory(uint32_t offset) -{ - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = 0; - payload.opcode = _curr_op = CMD_LIST_DIRECTORY; - payload.offset = offset; - strncpy(reinterpret_cast(payload.data), _last_path.c_str(), max_data_length - 1); - payload.size = _last_path.length() + 1; - - if (offset == 0) { - _curr_directory_list.clear(); - } - _send_mavlink_ftp_message(payload); -} - -void MavlinkFtp::_generic_command_async( - Opcode opcode, uint32_t offset, const std::string& path, ResultCallback callback) -{ - if (_curr_op != CMD_NONE) { - callback(ClientResult::Busy); - return; - } - if (path.length() >= max_data_length) { - callback(ClientResult::InvalidParameter); - return; - } - - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = 0; - payload.opcode = _curr_op = opcode; - payload.offset = offset; - strncpy(reinterpret_cast(payload.data), path.c_str(), max_data_length - 1); - payload.size = path.length() + 1; - - _curr_op_result_callback = callback; - _send_mavlink_ftp_message(payload); -} - -MavlinkFtp::ClientResult MavlinkFtp::create_directory(const std::string& path) -{ - std::promise prom; - auto fut = prom.get_future(); - - create_directory_async(path, [&prom](const ClientResult result) { prom.set_value(result); }); - - return fut.get(); -} - -void MavlinkFtp::create_directory_async(const std::string& path, ResultCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - _generic_command_async(CMD_CREATE_DIRECTORY, 0, path, callback); -} - -MavlinkFtp::ClientResult MavlinkFtp::remove_directory(const std::string& path) -{ - std::promise prom; - auto fut = prom.get_future(); - - remove_directory_async(path, [&prom](const ClientResult result) { prom.set_value(result); }); - - return fut.get(); -} - -void MavlinkFtp::remove_directory_async(const std::string& path, ResultCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - _generic_command_async(CMD_REMOVE_DIRECTORY, 0, path, callback); -} - -MavlinkFtp::ClientResult MavlinkFtp::remove_file(const std::string& path) -{ - std::promise prom; - auto fut = prom.get_future(); - - remove_file_async(path, [&prom](const ClientResult result) { prom.set_value(result); }); - - return fut.get(); -} - -void MavlinkFtp::remove_file_async(const std::string& path, ResultCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - _generic_command_async(CMD_REMOVE_FILE, 0, path, callback); -} - -MavlinkFtp::ClientResult -MavlinkFtp::rename(const std::string& from_path, const std::string& to_path) -{ - std::promise prom; - auto fut = prom.get_future(); - - rename_async( - from_path, to_path, [&prom](const ClientResult result) { prom.set_value(result); }); - - return fut.get(); -} - -void MavlinkFtp::rename_async( - const std::string& from_path, const std::string& to_path, ResultCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - if (_curr_op != CMD_NONE) { - callback(ClientResult::Busy); - return; - } - if (from_path.length() + to_path.length() + 1 >= max_data_length) { - callback(ClientResult::InvalidParameter); - return; - } - - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = 0; - payload.opcode = _curr_op = CMD_RENAME; - payload.offset = 0; - strncpy(reinterpret_cast(payload.data), from_path.c_str(), max_data_length - 1); - payload.size = from_path.length() + 1; - strncpy( - reinterpret_cast(&payload.data[payload.size]), - to_path.c_str(), - max_data_length - payload.size); - payload.size += to_path.length() + 1; - _curr_op_result_callback = callback; - _send_mavlink_ftp_message(payload); -} - -std::pair -MavlinkFtp::are_files_identical(const std::string& local_path, const std::string& remote_path) -{ - std::promise> prom; - auto fut = prom.get_future(); - - are_files_identical_async( - local_path, remote_path, [&prom](const ClientResult result, const bool are_identical) { - prom.set_value(std::make_pair(result, are_identical)); - }); - - return fut.get(); -} - -void MavlinkFtp::are_files_identical_async( - const std::string& local_path, - const std::string& remote_path, - AreFilesIdenticalCallback callback) -{ - if (!callback) { - return; - } - - auto temp_callback = callback; - - uint32_t crc_local = 0; - auto result_local = _calc_local_file_crc32(local_path, crc_local); - if (result_local != ClientResult::Success) { - _system_impl.call_user_callback( - [temp_callback, result_local]() { temp_callback(result_local, false); }); - return; - } - - _calc_file_crc32_async( - remote_path, - [this, crc_local, temp_callback](ClientResult result_remote, uint32_t crc_remote) { - if (result_remote != ClientResult::Success) { - _system_impl.call_user_callback( - [temp_callback, result_remote]() { temp_callback(result_remote, false); }); - } else { - _system_impl.call_user_callback([temp_callback, crc_local, crc_remote]() { - temp_callback(ClientResult::Success, crc_local == crc_remote); - }); - } - }); -} - -void MavlinkFtp::_calc_file_crc32_async(const std::string& path, file_crc32_ResultCallback callback) -{ - std::lock_guard lock(_curr_op_mutex); - if (_curr_op != CMD_NONE) { - callback(ClientResult::Busy, 0); - return; - } - if (path.length() >= max_data_length) { - callback(ClientResult::InvalidParameter, 0); - return; - } - - auto payload = PayloadHeader{}; - payload.seq_number = _seq_number++; - payload.session = 0; - payload.opcode = _curr_op = CMD_CALC_FILE_CRC32; - payload.offset = 0; - strncpy(reinterpret_cast(payload.data), path.c_str(), max_data_length - 1); - payload.size = path.length() + 1; - _current_crc32_result_callback = callback; - _send_mavlink_ftp_message(payload); -} - -void MavlinkFtp::_send_mavlink_ftp_message(const PayloadHeader& payload) -{ - mavlink_msg_file_transfer_protocol_pack( - _system_impl.get_own_system_id(), - _system_impl.get_own_component_id(), - &_last_command, - _network_id, - _system_impl.get_system_id(), - _get_target_component_id(), - reinterpret_cast(&payload)); - _system_impl.send_message(_last_command); - - _reset_timer(); - std::lock_guard lock(_timer_mutex); - if (!_last_command_timer_running) { - _last_command_timer_running = true; - _system_impl.register_timeout_handler( - [this]() { _command_timeout(); }, - static_cast(_last_command_timeout) / 1000.0, - &_last_command_timeout_cookie); - } -} - -void MavlinkFtp::_command_timeout() -{ - if (_last_command_retries >= _max_last_command_retries) { - LogErr() << "Response timeout " << _curr_op; - { - std::lock_guard lock(_timer_mutex); - _last_command_timer_running = false; - _session_result = ServerResult::ERR_TIMEOUT; - _session_valid = false; - } - _process_nak(ServerResult::ERR_TIMEOUT); - } else { - _last_command_retries++; - LogWarn() << "Response timeout. Retry: " << _last_command_retries; - _system_impl.send_message(_last_command); - _system_impl.register_timeout_handler( - [this]() { _command_timeout(); }, - static_cast(_last_command_timeout) / 1000.0, - &_last_command_timeout_cookie); - } -} - -void MavlinkFtp::_reset_timer() -{ - _system_impl.refresh_timeout_handler(_last_command_timeout_cookie); - _last_command_retries = 0; -} - -void MavlinkFtp::_stop_timer() -{ - { - std::lock_guard lock(_timer_mutex); - if (!_last_command_timer_running) { - return; - } - _last_command_timer_running = false; - } - _system_impl.unregister_timeout_handler(_last_command_timeout_cookie); -} - -/// @brief Guarantees that the payload data is null terminated. -/// @return Returns payload data as a std string -std::string MavlinkFtp::_data_as_string(PayloadHeader* payload) -{ - // guarantee null termination - if (payload->size < max_data_length) { - payload->data[payload->size] = '\0'; - - } else { - payload->data[max_data_length - 1] = '\0'; - } - - // and return data - return std::string(reinterpret_cast(&(payload->data[0]))); -} - -std::string MavlinkFtp::_get_path(PayloadHeader* payload) -{ - return _get_path(_data_as_string(payload)); -} - -MavlinkFtp::ClientResult MavlinkFtp::set_root_directory(const std::string& root_dir) -{ - _root_dir = fs_canonical(root_dir); - return ClientResult::Success; -} - -std::string MavlinkFtp::_get_path(const std::string& payload_path) -{ - return fs_canonical(_root_dir + path_separator + payload_path); -} - -std::string MavlinkFtp::_get_rel_path(const std::string& path) -{ - return path.substr(_root_dir.length()); -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_list(PayloadHeader* payload, bool list_hidden) -{ - ServerResult error_code = ServerResult::SUCCESS; - - uint8_t offset = 0; - // move to the requested offset - uint32_t requested_offset = payload->offset; - - std::string path = _get_path(payload); - if (path.rfind(_root_dir, 0) != 0) { - LogWarn() << "FTP: invalid path " << path; - return ServerResult::ERR_FAIL; - } - if (!fs_exists(path)) { - LogWarn() << "FTP: can't open path " << path; - // this is not an FTP error, abort directory by simulating eof - return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - - struct dirent* dp; - DIR* dfd = opendir(path.c_str()); - if (dfd != nullptr) { - while ((dp = readdir(dfd)) != nullptr) { - if (requested_offset > 0) { - requested_offset--; - continue; - } - - std::string filename = dp->d_name; - std::string full_path = path + path_separator + filename; - - std::string entry_s = DIRENT_SKIP; - if (list_hidden || filename.rfind(".", 0) != 0) { -#ifdef _DIRENT_HAVE_D_TYPE - bool type_reg = (dp->d_type == DT_REG); - bool type_dir = (dp->d_type == DT_DIR); -#else - struct stat statbuf; - stat(full_path.c_str(), &statbuf); - bool type_reg = S_ISREG(statbuf.st_mode); - bool type_dir = S_ISDIR(statbuf.st_mode); -#endif - if (type_reg) { - entry_s = DIRENT_FILE + _get_rel_path(full_path) + "\t" + - std::to_string(fs_file_size(full_path)); - } else if (type_dir) { - entry_s = DIRENT_DIR + _get_rel_path(full_path); - } - } - - // Do we have room for the dir entry and the null terminator? - if (offset + entry_s.length() + 1 > max_data_length) { - break; - } - uint8_t len = static_cast(entry_s.length() + 1); - memcpy(&payload->data[offset], entry_s.c_str(), len); - offset += len; - } - } - - payload->size = offset; - - return error_code; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_open(PayloadHeader* payload, int oflag) -{ - if (_session_info.fd >= 0) { - return ServerResult::ERR_NO_SESSIONS_AVAILABLE; - } - - std::string path = [payload, this]() { - std::lock_guard lock(_tmp_files_mutex); - const auto it = _tmp_files.find(_data_as_string(payload)); - if (it != _tmp_files.end()) { - return it->second; - } else { - return _get_path(payload); - } - }(); - - if (path.empty()) { - return ServerResult::ERR_FAIL; - } - - // TODO: check again - // if (path.rfind(_root_dir, 0) != 0) { - // LogWarn() << "FTP: invalid path " << path; - // return ServerResult::ERR_FAIL; - // } - - // fail only if requested open for read - if ((oflag & O_ACCMODE) == O_RDONLY && !fs_exists(path)) { - LogWarn() << "FTP: Open failed - file not found"; - return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - - uint32_t file_size = fs_file_size(path); - - // Set mode to 666 in case oflag has O_CREAT - int fd = ::open(path.c_str(), oflag, 0666); - - if (fd < 0) { - LogWarn() << "FTP: Open failed"; - return (errno == ENOENT) ? ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST : - ServerResult::ERR_FAIL; - } - - _session_info.fd = fd; - _session_info.file_size = file_size; - _session_info.stream_download = false; - - payload->session = 0; - payload->size = sizeof(uint32_t); - memcpy(payload->data, &file_size, payload->size); - - return ServerResult::SUCCESS; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_read(PayloadHeader* payload) -{ - if (payload->session != 0 || _session_info.fd < 0) { - return ServerResult::ERR_INVALID_SESSION; - } - - // We have to test seek past EOF ourselves, lseek will allow seek past EOF - if (payload->offset >= _session_info.file_size) { - return ServerResult::ERR_EOF; - } - - if (lseek(_session_info.fd, payload->offset, SEEK_SET) < 0) { - return ServerResult::ERR_FAIL; - } - - auto bytes_read = ::read(_session_info.fd, &payload->data[0], max_data_length); - - if (bytes_read < 0) { - // Negative return indicates error other than eof - return ServerResult::ERR_FAIL; - } - - payload->size = bytes_read; - - return ServerResult::SUCCESS; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_burst(PayloadHeader* payload) -{ - if (payload->session != 0 && _session_info.fd < 0) { - return ServerResult::ERR_INVALID_SESSION; - } - - // Setup for streaming sends - _session_info.stream_download = true; - _session_info.stream_offset = payload->offset; - _session_info.stream_chunk_transmitted = 0; - _session_info.stream_seq_number = payload->seq_number + 1; - _session_info.stream_target_system_id = _system_impl.get_system_id(); - - return ServerResult::SUCCESS; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_write(PayloadHeader* payload) -{ - if (payload->session != 0 && _session_info.fd < 0) { - return ServerResult::ERR_INVALID_SESSION; - } - - if (lseek(_session_info.fd, payload->offset, SEEK_SET) < 0) { - // Unable to see to the specified location - return ServerResult::ERR_FAIL; - } - - int bytes_written = ::write(_session_info.fd, &payload->data[0], payload->size); - - if (bytes_written < 0) { - // Negative return indicates error other than eof - return ServerResult::ERR_FAIL; - } - - payload->size = sizeof(uint32_t); - memcpy(payload->data, &bytes_written, payload->size); - - return ServerResult::SUCCESS; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_terminate(PayloadHeader* payload) -{ - if (payload->session != 0 || _session_info.fd < 0) { - return ServerResult::ERR_INVALID_SESSION; - } - - close(_session_info.fd); - _session_info.fd = -1; - _session_info.stream_download = false; - - payload->size = 0; - - return ServerResult::SUCCESS; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_reset(PayloadHeader* payload) -{ - if (_session_info.fd != -1) { - close(_session_info.fd); - _session_info.fd = -1; - _session_info.stream_download = false; - } - - payload->size = 0; - - return ServerResult::SUCCESS; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_remove_directory(PayloadHeader* payload) -{ - std::string path = _get_path(payload); - if (path.rfind(_root_dir, 0) != 0) { - LogWarn() << "FTP: invalid path " << path; - return ServerResult::ERR_FAIL; - } - - if (!fs_exists(path)) { - return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - if (fs_remove(path)) { - return ServerResult::SUCCESS; - } else { - return ServerResult::ERR_FAIL; - } -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_create_directory(PayloadHeader* payload) -{ - std::string path = _get_path(payload); - if (path.rfind(_root_dir, 0) != 0) { - LogWarn() << "FTP: invalid path " << path; - return ServerResult::ERR_FAIL; - } - - if (fs_exists(path)) { - return ServerResult::ERR_FAIL_FILE_EXISTS; - } - if (fs_create_directory(path)) { - return ServerResult::SUCCESS; - } else { - return ServerResult::ERR_FAIL_ERRNO; - } -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_remove_file(PayloadHeader* payload) -{ - std::string path = _get_path(payload); - if (path.rfind(_root_dir, 0) != 0) { - LogWarn() << "FTP: invalid path " << path; - return ServerResult::ERR_FAIL; - } - - if (!fs_exists(path)) { - return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - if (fs_remove(path)) { - return ServerResult::SUCCESS; - } else { - return ServerResult::ERR_FAIL; - } -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_rename(PayloadHeader* payload) -{ - size_t term_i = payload->size; - if (payload->size >= max_data_length) { - term_i = max_data_length - 1; - } - payload->data[term_i] = '\0'; - - std::string old_name = std::string(reinterpret_cast(&(payload->data[0]))); - std::string new_name = - _get_path(std::string(reinterpret_cast(&(payload->data[old_name.length() + 1])))); - old_name = _get_path(old_name); - if (old_name.rfind(_root_dir, 0) != 0 || new_name.rfind(_root_dir, 0) != 0) { - return ServerResult::ERR_FAIL; - } - - if (!fs_exists(old_name)) { - return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - - if (fs_rename(old_name, new_name)) { - return ServerResult::SUCCESS; - } else { - return ServerResult::ERR_FAIL; - } -} - -MavlinkFtp::ClientResult MavlinkFtp::_calc_local_file_crc32(const std::string& path, uint32_t& csum) -{ - if (!fs_exists(path)) { - return ClientResult::FileDoesNotExist; - } - - int fd = ::open(path.c_str(), O_RDONLY); - if (fd < 0) { - return ClientResult::FileIoError; - } - - // Read whole file in buffer size chunks - Crc32 checksum; - char buffer[18392]; - ssize_t bytes_read; - do { - bytes_read = ::read(fd, buffer, sizeof(buffer)); - - if (bytes_read < 0) { - int r_errno = errno; - close(fd); - errno = r_errno; - return ClientResult::FileIoError; - } - - checksum.add((uint8_t*)buffer, bytes_read); - } while (bytes_read == sizeof(buffer)); - - close(fd); - - csum = checksum.get(); - - return ClientResult::Success; -} - -MavlinkFtp::ServerResult MavlinkFtp::_work_calc_file_CRC32(PayloadHeader* payload) -{ - std::string path = _get_path(payload); - if (path.rfind(_root_dir, 0) != 0) { - LogWarn() << "FTP: invalid path " << path; - return ServerResult::ERR_FAIL; - } - - if (!fs_exists(path)) { - return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; - } - - payload->size = sizeof(uint32_t); - uint32_t checksum; - ClientResult res = _calc_local_file_crc32(path, checksum); - if (res != ClientResult::Success) { - return ServerResult::ERR_FILE_IO_ERROR; - } - *reinterpret_cast(payload->data) = checksum; - - return ServerResult::SUCCESS; -} - -void MavlinkFtp::send() -{ - // Anything to stream? - if (!_session_info.stream_download) { - return; - } -} - -uint8_t MavlinkFtp::get_our_compid() -{ - return _system_impl.get_own_component_id(); -} - -uint8_t MavlinkFtp::_get_target_component_id() -{ - return _target_component_id_set ? _target_component_id : _system_impl.get_autopilot_id(); -} - -MavlinkFtp::ClientResult MavlinkFtp::set_target_compid(uint8_t component_id) -{ - _target_component_id = component_id; - _target_component_id_set = true; - return ClientResult::Success; -} - -std::optional -MavlinkFtp::write_tmp_file(const std::string& path, const std::string& content) -{ - // TODO: Check if currently an operation is ongoing. - - if (path.find("..") != std::string::npos) { - LogWarn() << "Path with .. not supported."; - return {}; - } - - if (path.find('/') != std::string::npos) { - LogWarn() << "Path with / not supported."; - return {}; - } - - if (path.find('\\') != std::string::npos) { - LogWarn() << "Path with \\ not supported."; - return {}; - } - - // We use a temporary directory to put these - if (_tmp_dir.empty()) { - auto maybe_tmp_dir = create_tmp_directory("mavsdk-mavlink-ftp-tmp-files"); - if (maybe_tmp_dir) { - _tmp_dir = maybe_tmp_dir.value(); - } - // If we can't get a tmp dir, we'll just try to use our current working dir, - // or whatever is the root dir by default. - } - - const auto file_path = _tmp_dir + path_separator + path; - std::ofstream out(file_path); - out << content; - out.flush(); - if (out.bad()) { - LogWarn() << "Writing to " << file_path << " failed"; - out.close(); - return {}; - } else { - out.close(); - - std::lock_guard lock(_tmp_files_mutex); - _tmp_files[path] = file_path; - - return {file_path}; - } -} - -std::ostream& operator<<(std::ostream& str, MavlinkFtp::ClientResult const& result) -{ - switch (result) { - default: - // Fallthrough - case MavlinkFtp::ClientResult::Unknown: - return str << "Unknown"; - case MavlinkFtp::ClientResult::Success: - return str << "Success"; - case MavlinkFtp::ClientResult::Next: - return str << "Next"; - case MavlinkFtp::ClientResult::Timeout: - return str << "Timeout"; - case MavlinkFtp::ClientResult::Busy: - return str << "Busy"; - case MavlinkFtp::ClientResult::FileIoError: - return str << "FileIoError"; - case MavlinkFtp::ClientResult::FileExists: - return str << "FileExists"; - case MavlinkFtp::ClientResult::FileDoesNotExist: - return str << "FileDoesNotExist"; - case MavlinkFtp::ClientResult::FileProtected: - return str << "FileProtected"; - case MavlinkFtp::ClientResult::InvalidParameter: - return str << "InvalidParameter"; - case MavlinkFtp::ClientResult::Unsupported: - return str << "Unsupported"; - case MavlinkFtp::ClientResult::ProtocolError: - return str << "ProtocolError"; - case MavlinkFtp::ClientResult::NoSystem: - return str << "NoSystem"; - } -} - -} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_ftp_client.cpp b/src/mavsdk/core/mavlink_ftp_client.cpp new file mode 100644 index 0000000000..2b1f7187dc --- /dev/null +++ b/src/mavsdk/core/mavlink_ftp_client.cpp @@ -0,0 +1,1297 @@ +#include "mavlink_ftp_client.h" +#include "system_impl.h" +#include "plugin_base.h" +#include +#include +#include + +#include "crc32.h" + +namespace mavsdk { + +namespace fs = std::filesystem; + +MavlinkFtpClient::MavlinkFtpClient(SystemImpl& system_impl) : _system_impl(system_impl) +{ + if (const char* env_p = std::getenv("MAVSDK_FTP_DEBUGGING")) { + if (std::string(env_p) == "1") { + LogDebug() << "Ftp debugging is on."; + _debugging = true; + } + } + + _system_impl.register_mavlink_message_handler( + MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, + [this](const mavlink_message_t& message) { process_mavlink_ftp_message(message); }, + this); +} + +MavlinkFtpClient::~MavlinkFtpClient() +{ + _system_impl.unregister_all_mavlink_message_handlers(this); +} + +void MavlinkFtpClient::do_work() +{ + LockedQueue::Guard work_queue_guard(_work_queue); + + auto work = work_queue_guard.get_front(); + if (!work) { + return; + } + + if (work->started) { + return; + } + work->started = true; + + // We're mainly starting the process here. After that, it continues + // based on returned acks or timeouts. + + std::visit( + overloaded{ + [&](DownloadItem& item) { + if (!download_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](DownloadBurstItem& item) { + if (!download_burst_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](UploadItem& item) { + if (!upload_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](RemoveItem& item) { + if (!remove_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](RenameItem& item) { + if (!rename_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](CreateDirItem& item) { + if (!create_dir_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](RemoveDirItem& item) { + if (!remove_dir_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](CompareFilesItem& item) { + if (!compare_files_start(*work, item)) { + work_queue_guard.pop_front(); + } + }, + [&](ListDirItem& item) { + if (!list_dir_start(*work, item)) { + work_queue_guard.pop_front(); + } + }}, + work->item); +} + +void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) +{ + mavlink_file_transfer_protocol_t ftp_req; + mavlink_msg_file_transfer_protocol_decode(&msg, &ftp_req); + + if (ftp_req.target_system != 0 && ftp_req.target_system != _system_impl.get_own_system_id()) { + LogWarn() << "Received FTP with wrong target system ID!"; + return; + } + + if (ftp_req.target_component != 0 && + ftp_req.target_component != _system_impl.get_own_component_id()) { + LogWarn() << "Received FTP with wrong target component ID!"; + return; + } + + PayloadHeader* payload = reinterpret_cast(&ftp_req.payload[0]); + + if (payload->size > max_data_length) { + LogWarn() << "Received FTP payload with invalid size"; + return; + } else { + if (_debugging) { + LogDebug() << "FTP: opcode: " << (int)payload->opcode + << ", size: " << (int)payload->size << ", offset: " << (int)payload->offset + << ", seq: " << payload->seq_number; + } + } + + LockedQueue::Guard work_queue_guard(_work_queue); + + auto work = work_queue_guard.get_front(); + if (!work) { + return; + } + + if (work->last_opcode != payload->req_opcode) { + // Ignore + LogWarn() << "Ignore: last: " << (int)work->last_opcode + << ", req: " << (int)payload->req_opcode; + return; + } + if (work->last_received_seq_number != 0 && + work->last_received_seq_number == payload->seq_number) { + // We have already seen this ack/nak. + LogWarn() << "Already seen"; + return; + } + + std::visit( + overloaded{ + [&](DownloadItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_OPEN_FILE_RO || + payload->req_opcode == CMD_READ_FILE) { + // Whenever we do get an ack, + // reset the retry counter. + work->retries = RETRIES; + + if (!download_continue(*work, item, payload)) { + stop_timer(); + work_queue_guard.pop_front(); + } + } else if (payload->req_opcode == CMD_TERMINATE_SESSION) { + stop_timer(); + item.ofstream.close(); + item.callback(ClientResult::Success, {}); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload), {}); + work_queue_guard.pop_front(); + } + }, + [&](DownloadBurstItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_OPEN_FILE_RO || + payload->req_opcode == CMD_BURST_READ_FILE) { + // Whenever we do get an ack, + // reset the retry counter. + work->retries = RETRIES; + + if (!download_burst_continue(*work, item, payload)) { + stop_timer(); + work_queue_guard.pop_front(); + } + } else if (payload->req_opcode == CMD_TERMINATE_SESSION) { + stop_timer(); + item.ofstream.close(); + item.callback(ClientResult::Success, {}); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload), {}); + work_queue_guard.pop_front(); + } + }, + [&](UploadItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_CREATE_FILE || + payload->req_opcode == CMD_OPEN_FILE_WO || + payload->req_opcode == CMD_WRITE_FILE) { + // Whenever we do get an ack, + // reset the retry counter. + work->retries = RETRIES; + + if (!upload_continue(*work, item)) { + stop_timer(); + work_queue_guard.pop_front(); + } + } else if (payload->req_opcode == CMD_TERMINATE_SESSION) { + stop_timer(); + item.ifstream.close(); + item.callback(ClientResult::Success, {}); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload), {}); + work_queue_guard.pop_front(); + } + }, + [&](RemoveItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_REMOVE_FILE) { + stop_timer(); + item.callback(ClientResult::Success); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload)); + work_queue_guard.pop_front(); + } + }, + [&](RenameItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_RENAME) { + stop_timer(); + item.callback(ClientResult::Success); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload)); + work_queue_guard.pop_front(); + } + }, + [&](CreateDirItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_CREATE_DIRECTORY) { + stop_timer(); + item.callback(ClientResult::Success); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload)); + work_queue_guard.pop_front(); + } + }, + [&](RemoveDirItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_REMOVE_DIRECTORY) { + stop_timer(); + item.callback(ClientResult::Success); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload)); + work_queue_guard.pop_front(); + } + }, + [&](CompareFilesItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_CALC_FILE_CRC32) { + stop_timer(); + uint32_t remote_crc = *reinterpret_cast(payload->data); + item.callback(ClientResult::Success, remote_crc == item.local_crc); + work_queue_guard.pop_front(); + + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + item.callback(result_from_nak(payload), false); + work_queue_guard.pop_front(); + } + }, + [&](ListDirItem& item) { + if (payload->opcode == RSP_ACK) { + if (payload->req_opcode == CMD_LIST_DIRECTORY) { + // Whenever we do get an ack, reset the retry counter. + work->retries = RETRIES; + + if (!list_dir_continue(*work, item, payload)) { + stop_timer(); + work_queue_guard.pop_front(); + } + } else { + LogWarn() << "Unexpected ack"; + } + + } else if (payload->opcode == RSP_NAK) { + stop_timer(); + if (payload->data[0] == ERR_EOF) { + std::sort(item.dirs.begin(), item.dirs.end()); + item.callback(ClientResult::Success, item.dirs); + } else { + item.callback(result_from_nak(payload), {}); + } + work_queue_guard.pop_front(); + } + }}, + work->item); + + work->last_received_seq_number = payload->seq_number; +} + +bool MavlinkFtpClient::download_start(Work& work, DownloadItem& item) +{ + fs::path local_path = fs::path(item.local_folder) / fs::path(item.remote_path).filename(); + + if (_debugging) { + LogDebug() << "Trying to open write to local path: " << local_path.string(); + } + + item.ofstream.open(local_path, std::fstream::trunc | std::fstream::binary); + if (!item.ofstream) { + LogErr() << "Could not open it!"; + item.callback(ClientResult::FileIoError, {}); + return false; + } + + work.last_opcode = CMD_OPEN_FILE_RO; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy( + reinterpret_cast(work.payload.data), item.remote_path.c_str(), max_data_length - 1); + work.payload.size = item.remote_path.length() + 1; + + start_timer(); + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::download_continue(Work& work, DownloadItem& item, PayloadHeader* payload) +{ + if (payload->req_opcode == CMD_OPEN_FILE_RO) { + item.file_size = *(reinterpret_cast(payload->data)); + + if (_debugging) { + LogWarn() << "Download continue, got file size: " << item.file_size; + } + + } else if (payload->req_opcode == CMD_READ_FILE) { + if (_debugging) { + LogWarn() << "Download continue, write: " << std::to_string(payload->size); + } + + if (item.bytes_transferred < item.file_size) { + item.ofstream.write(reinterpret_cast(payload->data), payload->size); + if (!item.ofstream) { + item.callback(ClientResult::FileIoError, {}); + return false; + } + item.bytes_transferred += payload->size; + + if (_debugging) { + LogDebug() << "Written " << item.bytes_transferred << " of " << item.file_size + << " bytes"; + } + } + item.callback( + ClientResult::Next, + ProgressData{ + static_cast(item.bytes_transferred), + static_cast(item.file_size)}); + } + + if (item.bytes_transferred < item.file_size) { + work.last_opcode = CMD_READ_FILE; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = _session; + work.payload.opcode = work.last_opcode; + work.payload.offset = item.bytes_transferred; + + work.payload.size = + std::min(static_cast(max_data_length), item.file_size - item.bytes_transferred); + + if (_debugging) { + LogWarn() << "Request size: " << std::to_string(work.payload.size) << " of left " + << int(item.file_size - item.bytes_transferred); + } + + start_timer(); + send_mavlink_ftp_message(work.payload); + + return true; + } else { + if (_debugging) { + LogDebug() << "All bytes written, terminating session"; + } + + // Final step + work.last_opcode = CMD_TERMINATE_SESSION; + + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = _session; + + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + work.payload.size = 0; + + start_timer(); + send_mavlink_ftp_message(work.payload); + } + + return true; +} + +bool MavlinkFtpClient::download_burst_start(Work& work, DownloadBurstItem& item) +{ + fs::path local_path = fs::path(item.local_folder) / fs::path(item.remote_path).filename(); + + if (_debugging) { + LogDebug() << "Trying to open write to local path: " << local_path.string(); + } + + item.ofstream.open(local_path, std::fstream::trunc | std::fstream::binary); + if (!item.ofstream) { + LogErr() << "Could not open it!"; + item.callback(ClientResult::FileIoError, {}); + return false; + } + + work.last_opcode = CMD_OPEN_FILE_RO; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy( + reinterpret_cast(work.payload.data), item.remote_path.c_str(), max_data_length - 1); + work.payload.size = item.remote_path.length() + 1; + + start_timer(); + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::download_burst_continue( + Work& work, DownloadBurstItem& item, PayloadHeader* payload) +{ + if (payload->req_opcode == CMD_OPEN_FILE_RO) { + const size_t file_size = *(reinterpret_cast(payload->data)); + item.transferred.resize(file_size, DownloadBurstItem::Transferred::No); + + // We just use a vector of 0 and write that to the file to prepare it. + // We then fill in the chunks as they come in. + std::vector empty; + empty.resize(file_size); + item.ofstream.write(empty.data(), empty.size()); + + if (_debugging) { + LogDebug() << "Burst Download continue, got file size: " << file_size; + } + + request_next_burst(work, item); + return true; + + } else if (payload->req_opcode == CMD_BURST_READ_FILE) { + if (_debugging) { + LogDebug() << "Burst download continue, at: " << std::to_string(payload->offset) + << " write: " << std::to_string(payload->size); + } + + item.ofstream.seekp(payload->offset); + if (item.ofstream.fail()) { + LogWarn() << "Seek failed"; + item.callback(ClientResult::FileIoError, {}); + return false; + } + + // Write actual data to file. + item.ofstream.write(reinterpret_cast(payload->data), payload->size); + if (!item.ofstream) { + LogWarn() << "Write failed"; + item.callback(ClientResult::FileIoError, {}); + return false; + } + + // Keep track of what was written. + for (size_t i = payload->offset; i < payload->offset + payload->size; ++i) { + item.transferred[i] = DownloadBurstItem::Transferred::Yes; + } + + const size_t bytes_transferred = std::count( + item.transferred.begin(), item.transferred.end(), DownloadBurstItem::Transferred::Yes); + + if (bytes_transferred == item.transferred.size()) { + if (_debugging) { + LogDebug() << "Burst complete"; + } + + // Final step + work.last_opcode = CMD_TERMINATE_SESSION; + + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = _session; + + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + work.payload.size = 0; + + start_timer(); + send_mavlink_ftp_message(work.payload); + + return true; + + } else { + item.callback( + ClientResult::Next, + ProgressData{ + static_cast(bytes_transferred), + static_cast(item.transferred.size())}); + + if (payload->burst_complete) { + // The burst is supposedly complete but we still need data, so request next burst. + request_next_burst(work, item); + + } else { + // There might be more coming, just wait for now. + start_timer(); + } + + return true; + } + + } else { + LogErr() << "Unexpected req_opcode"; + return false; + } +} + +void MavlinkFtpClient::request_next_burst(Work& work, DownloadBurstItem& item) +{ + const auto first_missing = std::find( + item.transferred.begin(), item.transferred.end(), DownloadBurstItem::Transferred::No); + if (first_missing == item.transferred.end()) { + LogErr() << "Nothing missing, this doesn't make sense."; + return; + } + + const auto last_missing_plus_one = + std::find(first_missing, item.transferred.end(), DownloadBurstItem::Transferred::Yes); + + const size_t offset = std::distance(item.transferred.begin(), first_missing); + const uint32_t size = + static_cast(std::distance(first_missing, last_missing_plus_one)); + + if (size == 0) { + LogErr() << "Size is 0"; + return; + } + + work.last_opcode = CMD_BURST_READ_FILE; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = _session; + work.payload.opcode = work.last_opcode; + work.payload.offset = offset; + + work.payload.size = 4; + std::memcpy(&work.payload.data, &size, 4); + + start_timer(); + send_mavlink_ftp_message(work.payload); +} + +bool MavlinkFtpClient::upload_start(Work& work, UploadItem& item) +{ + std::error_code ec; + if (!fs::exists(item.local_file_path, ec)) { + item.callback(ClientResult::FileDoesNotExist, {}); + return false; + } + + item.ifstream.open(item.local_file_path, std::fstream::binary); + if (!item.ifstream) { + item.callback(ClientResult::FileIoError, {}); + return false; + } + + item.file_size = fs::file_size(item.local_file_path, ec); + if (ec) { + LogWarn() << "Could not get file size of '" << item.local_file_path + << "': " << ec.message(); + return false; + } + + fs::path remote_file_path = + fs::path(item.remote_folder) / fs::path(item.local_file_path).filename(); + + if (remote_file_path.string().size() >= max_data_length) { + item.callback(ClientResult::InvalidParameter, {}); + return false; + } + + work.last_opcode = CMD_CREATE_FILE; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy( + reinterpret_cast(work.payload.data), + remote_file_path.string().c_str(), + max_data_length - 1); + work.payload.size = remote_file_path.string().size() + 1; + + start_timer(); + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::upload_continue(Work& work, UploadItem& item) +{ + if (item.bytes_transferred < item.file_size) { + work.last_opcode = CMD_WRITE_FILE; + + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = _session; + + work.payload.opcode = work.last_opcode; + work.payload.offset = item.bytes_transferred; + + std::size_t bytes_to_read = + std::min(item.file_size - item.bytes_transferred, std::size_t(max_data_length)); + + item.ifstream.read(reinterpret_cast(work.payload.data), bytes_to_read); + + // Get the number of bytes actually read. + int bytes_read = item.ifstream.gcount(); + + if (!item.ifstream) { + item.callback(ClientResult::FileIoError, {}); + return false; + } + + work.payload.size = bytes_read; + item.bytes_transferred += bytes_read; + + start_timer(); + send_mavlink_ftp_message(work.payload); + + } else { + // Final step + work.last_opcode = CMD_TERMINATE_SESSION; + + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = _session; + + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + work.payload.size = 0; + + start_timer(); + send_mavlink_ftp_message(work.payload); + } + + item.callback( + ClientResult::Next, + ProgressData{ + static_cast(item.bytes_transferred), static_cast(item.file_size)}); + + return true; +} + +bool MavlinkFtpClient::remove_start(Work& work, RemoveItem& item) +{ + if (item.path.length() >= max_data_length) { + item.callback(ClientResult::InvalidParameter); + return false; + } + + work.last_opcode = CMD_REMOVE_FILE; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy(reinterpret_cast(work.payload.data), item.path.c_str(), max_data_length - 1); + work.payload.size = item.path.length() + 1; + + start_timer(); + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::rename_start(Work& work, RenameItem& item) +{ + if (item.from_path.length() + item.to_path.length() + 1 >= max_data_length) { + item.callback(ClientResult::InvalidParameter); + return false; + } + + work.last_opcode = CMD_RENAME; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy( + reinterpret_cast(work.payload.data), item.from_path.c_str(), max_data_length - 1); + work.payload.size = item.from_path.length() + 1; + strncpy( + reinterpret_cast(&work.payload.data[work.payload.size]), + item.to_path.c_str(), + max_data_length - work.payload.size); + work.payload.size += item.to_path.length() + 1; + start_timer(); + + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::create_dir_start(Work& work, CreateDirItem& item) +{ + if (item.path.length() + 1 >= max_data_length) { + item.callback(ClientResult::InvalidParameter); + return false; + } + + work.last_opcode = CMD_CREATE_DIRECTORY; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy(reinterpret_cast(work.payload.data), item.path.c_str(), max_data_length - 1); + work.payload.size = item.path.length() + 1; + start_timer(); + + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::remove_dir_start(Work& work, RemoveDirItem& item) +{ + if (item.path.length() + 1 >= max_data_length) { + item.callback(ClientResult::InvalidParameter); + return false; + } + + work.last_opcode = CMD_REMOVE_DIRECTORY; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy(reinterpret_cast(work.payload.data), item.path.c_str(), max_data_length - 1); + work.payload.size = item.path.length() + 1; + start_timer(); + + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::compare_files_start(Work& work, CompareFilesItem& item) +{ + if (item.remote_path.length() + 1 >= max_data_length) { + item.callback(ClientResult::InvalidParameter, false); + return false; + } + + auto result_local = calc_local_file_crc32(item.local_path, item.local_crc); + if (result_local != ClientResult::Success) { + item.callback(result_local, false); + return false; + } + + work.last_opcode = CMD_CALC_FILE_CRC32; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy( + reinterpret_cast(work.payload.data), item.remote_path.c_str(), max_data_length - 1); + work.payload.size = item.remote_path.length() + 1; + start_timer(); + + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::list_dir_start(Work& work, ListDirItem& item) +{ + if (item.path.length() + 1 >= max_data_length) { + item.callback(ClientResult::InvalidParameter, {}); + return false; + } + + work.last_opcode = CMD_LIST_DIRECTORY; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = 0; + strncpy(reinterpret_cast(work.payload.data), item.path.c_str(), max_data_length - 1); + work.payload.size = item.path.length() + 1; + start_timer(); + + send_mavlink_ftp_message(work.payload); + + return true; +} + +bool MavlinkFtpClient::list_dir_continue(Work& work, ListDirItem& item, PayloadHeader* payload) +{ + if (_debugging) { + LogDebug() << "List dir response received, got " << (int)payload->size << " chars"; + } + + if (payload->size > max_data_length) { + LogWarn() << "Received FTP payload with invalid size"; + return false; + } + + // Make sure there is a zero termination. + payload->data[payload->size - 1] = '\0'; + + size_t i = 0; + while (i + 1 < payload->size) { + const int entry_len = std::strlen(reinterpret_cast(&payload->data[i])); + + std::string entry; + entry.resize(entry_len); + std::memcpy(entry.data(), &payload->data[i], entry_len); + + i += entry_len + 1; + + ++item.offset; + + if (entry[0] == 'S') { + // Skip skip for now + continue; + } + + item.dirs.push_back(entry); + } + + work.last_opcode = CMD_LIST_DIRECTORY; + work.payload = {}; + work.payload.seq_number = work.last_sent_seq_number++; + work.payload.session = 0; + work.payload.opcode = work.last_opcode; + work.payload.offset = item.offset; + strncpy(reinterpret_cast(work.payload.data), item.path.c_str(), max_data_length - 1); + work.payload.size = item.path.length() + 1; + start_timer(); + + send_mavlink_ftp_message(work.payload); + + return true; +} + +MavlinkFtpClient::ClientResult MavlinkFtpClient::result_from_nak(PayloadHeader* payload) +{ + ServerResult sr = static_cast(payload->data[0]); + + // PX4 Mavlink FTP returns "File doesn't exist" this way + if (sr == ServerResult::ERR_FAIL_ERRNO && payload->data[1] == ENOENT) { + sr = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + } + + return translate(sr); +} + +MavlinkFtpClient::ClientResult MavlinkFtpClient::translate(ServerResult result) +{ + switch (result) { + case ServerResult::SUCCESS: + return ClientResult::Success; + case ServerResult::ERR_TIMEOUT: + return ClientResult::Timeout; + case ServerResult::ERR_FILE_IO_ERROR: + return ClientResult::FileIoError; + case ServerResult::ERR_FAIL_FILE_EXISTS: + return ClientResult::FileExists; + case ServerResult::ERR_FAIL_FILE_PROTECTED: + return ClientResult::FileProtected; + case ServerResult::ERR_UNKOWN_COMMAND: + return ClientResult::Unsupported; + case ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST: + return ClientResult::FileDoesNotExist; + default: + return ClientResult::ProtocolError; + } +} + +void MavlinkFtpClient::download_async( + const std::string& remote_path, + const std::string& local_folder, + bool use_burst, + DownloadCallback callback) +{ + if (use_burst) { + auto item = DownloadBurstItem{}; + item.remote_path = remote_path; + item.local_folder = local_folder; + item.callback = callback; + auto new_work = Work{std::move(item)}; + _work_queue.push_back(std::make_shared(std::move(new_work))); + + } else { + auto item = DownloadItem{}; + item.remote_path = remote_path; + item.local_folder = local_folder; + item.callback = callback; + auto new_work = Work{std::move(item)}; + _work_queue.push_back(std::make_shared(std::move(new_work))); + } +} + +void MavlinkFtpClient::upload_async( + const std::string& local_file_path, const std::string& remote_folder, UploadCallback callback) +{ + auto item = UploadItem{}; + item.local_file_path = local_file_path; + item.remote_folder = remote_folder; + item.callback = callback; + auto new_work = Work{std::move(item)}; + + _work_queue.push_back(std::make_shared(std::move(new_work))); +} + +void MavlinkFtpClient::list_directory_async(const std::string& path, ListDirectoryCallback callback) +{ + auto item = ListDirItem{}; + item.path = path; + item.callback = callback; + auto new_work = Work{std::move(item)}; + + _work_queue.push_back(std::make_shared(std::move(new_work))); +} + +void MavlinkFtpClient::create_directory_async(const std::string& path, ResultCallback callback) +{ + auto item = CreateDirItem{}; + item.path = path; + item.callback = callback; + auto new_work = Work{std::move(item)}; + + _work_queue.push_back(std::make_shared(std::move(new_work))); +} + +void MavlinkFtpClient::remove_directory_async(const std::string& path, ResultCallback callback) +{ + auto item = RemoveDirItem{}; + item.path = path; + item.callback = callback; + auto new_work = Work{std::move(item)}; + + _work_queue.push_back(std::make_shared(std::move(new_work))); +} + +void MavlinkFtpClient::remove_file_async(const std::string& path, ResultCallback callback) +{ + auto item = RemoveItem{}; + item.path = path; + item.callback = callback; + auto new_work = Work{std::move(item)}; + + _work_queue.push_back(std::make_shared(std::move(new_work))); +} + +void MavlinkFtpClient::rename_async( + const std::string& from_path, const std::string& to_path, ResultCallback callback) +{ + auto item = RenameItem{}; + item.from_path = from_path; + item.to_path = to_path; + item.callback = callback; + auto new_work = Work{std::move(item)}; + + _work_queue.push_back(std::make_shared(std::move(new_work))); +} + +void MavlinkFtpClient::are_files_identical_async( + const std::string& local_path, + const std::string& remote_path, + AreFilesIdenticalCallback callback) +{ + auto item = CompareFilesItem{}; + item.local_path = local_path; + item.remote_path = remote_path; + item.callback = callback; + auto new_work = Work{std::move(item)}; + + _work_queue.push_back(std::make_shared(std::move(new_work))); +} + +void MavlinkFtpClient::send_mavlink_ftp_message(const PayloadHeader& payload) +{ + _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message; + mavlink_msg_file_transfer_protocol_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &message, + _network_id, + _system_impl.get_system_id(), + get_target_component_id(), + reinterpret_cast(&payload)); + return message; + }); +} + +void MavlinkFtpClient::start_timer() +{ + _system_impl.unregister_timeout_handler(_timeout_cookie); + _system_impl.register_timeout_handler( + [this]() { timeout(); }, _system_impl.timeout_s(), &_timeout_cookie); +} + +void MavlinkFtpClient::stop_timer() +{ + _system_impl.unregister_timeout_handler(_timeout_cookie); +} + +void MavlinkFtpClient::timeout() +{ + if (_debugging) { + LogDebug() << "Timeout!"; + } + + LockedQueue::Guard work_queue_guard(_work_queue); + auto work = work_queue_guard.get_front(); + if (!work) { + return; + } + + std::visit( + overloaded{ + [&](DownloadItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout, {}); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](DownloadBurstItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout, {}); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](UploadItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout, {}); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](RemoveItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](RenameItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](CreateDirItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](RemoveDirItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](CompareFilesItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout, false); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }, + [&](ListDirItem& item) { + if (--work->retries == 0) { + item.callback(ClientResult::Timeout, {}); + work_queue_guard.pop_front(); + return; + } + if (_debugging) { + LogDebug() << "Retries left: " << work->retries; + } + + start_timer(); + send_mavlink_ftp_message(work->payload); + }}, + work->item); +} + +MavlinkFtpClient::ClientResult +MavlinkFtpClient::calc_local_file_crc32(const std::string& path, uint32_t& csum) +{ + std::error_code ec; + if (!fs::exists(path, ec)) { + return ClientResult::FileDoesNotExist; + } + + std::ifstream stream(path, std::fstream::binary); + if (!stream) { + return ClientResult::FileIoError; + } + + // Read whole file in buffer size chunks + Crc32 checksum; + uint8_t buffer[4096]; + std::streamsize bytes_read; + + do { + stream.read(reinterpret_cast(buffer), sizeof(buffer)); + bytes_read = stream.gcount(); // Get the number of bytes actually read + checksum.add(reinterpret_cast(buffer), bytes_read); + } while (bytes_read > 0); + + csum = checksum.get(); + + return ClientResult::Success; +} + +uint8_t MavlinkFtpClient::get_our_compid() +{ + return _system_impl.get_own_component_id(); +} + +uint8_t MavlinkFtpClient::get_target_component_id() +{ + return _target_component_id_set ? _target_component_id : _system_impl.get_autopilot_id(); +} + +MavlinkFtpClient::ClientResult MavlinkFtpClient::set_target_compid(uint8_t component_id) +{ + _target_component_id = component_id; + _target_component_id_set = true; + return ClientResult::Success; +} + +std::ostream& operator<<(std::ostream& str, MavlinkFtpClient::ClientResult const& result) +{ + switch (result) { + default: + // Fallthrough + case MavlinkFtpClient::ClientResult::Unknown: + return str << "Unknown"; + case MavlinkFtpClient::ClientResult::Success: + return str << "Success"; + case MavlinkFtpClient::ClientResult::Next: + return str << "Next"; + case MavlinkFtpClient::ClientResult::Timeout: + return str << "Timeout"; + case MavlinkFtpClient::ClientResult::Busy: + return str << "Busy"; + case MavlinkFtpClient::ClientResult::FileIoError: + return str << "FileIoError"; + case MavlinkFtpClient::ClientResult::FileExists: + return str << "FileExists"; + case MavlinkFtpClient::ClientResult::FileDoesNotExist: + return str << "FileDoesNotExist"; + case MavlinkFtpClient::ClientResult::FileProtected: + return str << "FileProtected"; + case MavlinkFtpClient::ClientResult::InvalidParameter: + return str << "InvalidParameter"; + case MavlinkFtpClient::ClientResult::Unsupported: + return str << "Unsupported"; + case MavlinkFtpClient::ClientResult::ProtocolError: + return str << "ProtocolError"; + case MavlinkFtpClient::ClientResult::NoSystem: + return str << "NoSystem"; + } +} + +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_ftp.h b/src/mavsdk/core/mavlink_ftp_client.h similarity index 60% rename from src/mavsdk/core/mavlink_ftp.h rename to src/mavsdk/core/mavlink_ftp_client.h index 07b6e3dab5..0179c2234a 100644 --- a/src/mavsdk/core/mavlink_ftp.h +++ b/src/mavsdk/core/mavlink_ftp_client.h @@ -8,9 +8,11 @@ #include #include #include +#include #include #include "mavlink_include.h" +#include "locked_queue.h" // As found in // https://stackoverflow.com/questions/1537964#answer-3312896 @@ -24,10 +26,10 @@ namespace mavsdk { class SystemImpl; -class MavlinkFtp { +class MavlinkFtpClient { public: - explicit MavlinkFtp(SystemImpl& system_impl); - ~MavlinkFtp(); + explicit MavlinkFtpClient(SystemImpl& system_impl); + ~MavlinkFtpClient(); /** * @brief Possible results returned for FTP commands @@ -61,27 +63,19 @@ class MavlinkFtp { using ListDirectoryCallback = std::function)>; using AreFilesIdenticalCallback = std::function; - void send(); - - std::pair> list_directory(const std::string& path); - ClientResult create_directory(const std::string& path); - ClientResult remove_directory(const std::string& path); - ClientResult remove_file(const std::string& path); - ClientResult rename(const std::string& from_path, const std::string& to_path); - std::pair - are_files_identical(const std::string& local_path, const std::string& remote_path); + void do_work(); void reset_async(ResultCallback callback); void download_async( const std::string& remote_file_path, const std::string& local_folder, + bool use_burst, DownloadCallback callback); void upload_async( const std::string& local_file_path, const std::string& remote_folder, UploadCallback callback); - void list_directory_async( - const std::string& path, ListDirectoryCallback callback, uint32_t offset = 0); + void list_directory_async(const std::string& path, ListDirectoryCallback callback); void create_directory_async(const std::string& path, ResultCallback callback); void remove_directory_async(const std::string& path, ResultCallback callback); void remove_file_async(const std::string& path, ResultCallback callback); @@ -92,34 +86,32 @@ class MavlinkFtp { const std::string& remote_path, AreFilesIdenticalCallback callback); - void set_retries(uint32_t retries) { _max_last_command_retries = retries; } ClientResult set_root_directory(const std::string& root_dir); uint8_t get_our_compid(); ClientResult set_target_compid(uint8_t component_id); - std::optional write_tmp_file(const std::string& path, const std::string& content); - private: - SystemImpl& _system_impl; + static constexpr unsigned RETRIES = 10; - /// @brief Possible server results returned for requests. - enum ServerResult : uint8_t { - SUCCESS, - ERR_FAIL, ///< Unknown failure - ERR_FAIL_ERRNO, ///< Command failed, errno sent back in PayloadHeader.data[1] - ERR_INVALID_DATA_SIZE, ///< PayloadHeader.size is invalid - ERR_INVALID_SESSION, ///< Session is not currently open - ERR_NO_SESSIONS_AVAILABLE, ///< All available Sessions in use - ERR_EOF, ///< Offset past end of file for List and Read commands - ERR_UNKOWN_COMMAND, ///< Unknown command opcode - ERR_FAIL_FILE_EXISTS, ///< File exists already - ERR_FAIL_FILE_PROTECTED, ///< File is write protected - ERR_FAIL_FILE_DOES_NOT_EXIST, ///< File does not exist + /// @brief Maximum data size in RequestHeader::data + static constexpr uint8_t max_data_length = 239; - // These error codes are returned to client without contacting the server - ERR_TIMEOUT = 200, ///< Timeout - ERR_FILE_IO_ERROR, ///< File IO operation error - }; + /// @brief This is the payload which is in mavlink_file_transfer_protocol_t.payload. + /// This needs to be packed, because it's typecasted from + /// mavlink_file_transfer_protocol_t.payload, which starts at a 3 byte offset, causing an + /// unaligned access to seq_number and offset + PACK(struct PayloadHeader { + uint16_t seq_number; ///< sequence number for message + uint8_t session; ///< Session id for read and write commands + uint8_t opcode; ///< Command opcode + uint8_t size; ///< Size of data + uint8_t req_opcode; ///< Request opcode returned in RSP_ACK, RSP_NAK message + uint8_t burst_complete; ///< Only used if req_opcode=CMD_BURST_READ_FILE - 1: set of burst + ///< packets complete, 0: More burst packets coming. + uint8_t padding; ///< 32 bit alignment padding + uint32_t offset; ///< Offsets for List and Read commands + uint8_t data[max_data_length]; ///< command data, varies by Opcode + }); /// @brief Command opcodes enum Opcode : uint8_t { @@ -144,32 +136,119 @@ class MavlinkFtp { RSP_NAK ///< Nak response }; - using file_crc32_ResultCallback = std::function; + struct DownloadItem { + std::string remote_path{}; + std::string local_folder{}; + DownloadCallback callback{}; + std::ofstream ofstream{}; + std::size_t file_size{0}; + std::size_t bytes_transferred{0}; + int last_progress_percentage{-1}; + }; + + struct DownloadBurstItem { + std::string remote_path{}; + std::string local_folder{}; + DownloadCallback callback{}; + std::ofstream ofstream{}; + enum class Transferred { + No, + Yes, + }; + std::vector transferred{}; + int last_progress_percentage{-1}; + }; + + struct UploadItem { + std::string local_file_path{}; + std::string remote_folder{}; + UploadCallback callback{}; + std::ifstream ifstream{}; + std::size_t file_size{0}; + std::size_t bytes_transferred{0}; + int last_progress_percentage{-1}; + }; + + struct RemoveItem { + std::string path{}; + ResultCallback callback{}; + }; + + struct RenameItem { + std::string from_path{}; + std::string to_path{}; + ResultCallback callback{}; + }; + + struct CreateDirItem { + std::string path{}; + ResultCallback callback{}; + }; + + struct RemoveDirItem { + std::string path{}; + ResultCallback callback{}; + }; + + struct CompareFilesItem { + std::string local_path{}; + std::string remote_path{}; + uint32_t local_crc{}; + AreFilesIdenticalCallback callback{}; + }; + + struct ListDirItem { + std::string path{}; + ListDirectoryCallback callback{}; + uint32_t offset{0}; + std::vector dirs{}; + }; + + using Item = std::variant< + DownloadItem, + DownloadBurstItem, + UploadItem, + RemoveItem, + RenameItem, + CreateDirItem, + RemoveDirItem, + CompareFilesItem, + ListDirItem>; + + struct Work { + Item item; + PayloadHeader payload; // The last payload saved for retries + unsigned retries{RETRIES}; + bool started{false}; + Opcode last_opcode{}; + uint16_t last_received_seq_number{0}; + uint16_t last_sent_seq_number{0}; + Work(Item new_item) : item(std::move(new_item)) {} + }; + + /// @brief Possible server results returned for requests. + enum ServerResult : uint8_t { + SUCCESS, + ERR_FAIL, ///< Unknown failure + ERR_FAIL_ERRNO, ///< Command failed, errno sent back in PayloadHeader.data[1] + ERR_INVALID_DATA_SIZE, ///< PayloadHeader.size is invalid + ERR_INVALID_SESSION, ///< Session is not currently open + ERR_NO_SESSIONS_AVAILABLE, ///< All available Sessions in use + ERR_EOF, ///< Offset past end of file for List and Read commands + ERR_UNKOWN_COMMAND, ///< Unknown command opcode + ERR_FAIL_FILE_EXISTS, ///< File exists already + ERR_FAIL_FILE_PROTECTED, ///< File is write protected + ERR_FAIL_FILE_DOES_NOT_EXIST, ///< File does not exist + + // These error codes are returned to client without contacting the server + ERR_TIMEOUT = 200, ///< Timeout + ERR_FILE_IO_ERROR, ///< File IO operation error + }; static constexpr auto DIRENT_FILE = "F"; ///< Identifies File returned from List command static constexpr auto DIRENT_DIR = "D"; ///< Identifies Directory returned from List command static constexpr auto DIRENT_SKIP = "S"; ///< Identifies Skipped entry from List command - /// @brief Maximum data size in RequestHeader::data - static constexpr uint8_t max_data_length = 239; - - /// @brief This is the payload which is in mavlink_file_transfer_protocol_t.payload. - /// This needs to be packed, because it's typecasted from - /// mavlink_file_transfer_protocol_t.payload, which starts at a 3 byte offset, causing an - /// unaligned access to seq_number and offset - PACK(struct PayloadHeader { - uint16_t seq_number; ///< sequence number for message - uint8_t session; ///< Session id for read and write commands - uint8_t opcode; ///< Command opcode - uint8_t size; ///< Size of data - uint8_t req_opcode; ///< Request opcode returned in RSP_ACK, RSP_NAK message - uint8_t burst_complete; ///< Only used if req_opcode=CMD_BURST_READ_FILE - 1: set of burst - ///< packets complete, 0: More burst packets coming. - uint8_t padding; ///< 32 bit alignment padding - uint32_t offset; ///< Offsets for List and Read commands - uint8_t data[max_data_length]; ///< command data, varies by Opcode - }); - static_assert( sizeof(PayloadHeader) == sizeof(mavlink_file_transfer_protocol_t::payload), "PayloadHeader size is incorrect."); @@ -184,103 +263,56 @@ class MavlinkFtp { unsigned stream_chunk_transmitted{0}; }; - struct OfstreamWithPath { - std::ofstream stream; - std::string path; - }; + bool download_start(Work& work, DownloadItem& item); + bool download_continue(Work& work, DownloadItem& item, PayloadHeader* payload); - struct SessionInfo _session_info {}; ///< Session info, fd=-1 for no active session + bool download_burst_start(Work& work, DownloadBurstItem& item); + bool download_burst_continue(Work& work, DownloadBurstItem& item, PayloadHeader* payload); + void request_next_burst(Work& work, DownloadBurstItem& item); + + bool upload_start(Work& work, UploadItem& item); + bool upload_continue(Work& work, UploadItem& item); + + bool remove_start(Work& work, RemoveItem& item); + + bool rename_start(Work& work, RenameItem& item); + + bool create_dir_start(Work& work, CreateDirItem& item); + + bool remove_dir_start(Work& work, RemoveDirItem& item); + + bool compare_files_start(Work& work, CompareFilesItem& item); + + bool list_dir_start(Work& work, ListDirItem& item); + bool list_dir_continue(Work& work, ListDirItem& item, PayloadHeader* payload); + + static ClientResult result_from_nak(PayloadHeader* payload); + + void timeout(); + void start_timer(); + void stop_timer(); + + ClientResult calc_local_file_crc32(const std::string& path, uint32_t& csum); + + static ClientResult translate(ServerResult result); + void send_mavlink_ftp_message(const PayloadHeader& payload); + + uint8_t get_target_component_id(); + + void process_mavlink_ftp_message(const mavlink_message_t& msg); + + SystemImpl& _system_impl; - uint8_t _network_id = 0; uint8_t _target_component_id = 0; bool _target_component_id_set{false}; - Opcode _curr_op = CMD_NONE; - std::mutex _curr_op_mutex{}; - mavlink_message_t _last_command{}; - void* _last_command_timeout_cookie = nullptr; - bool _last_command_timer_running{false}; - std::mutex _timer_mutex{}; - static constexpr uint32_t _last_command_timeout{200}; - uint32_t _max_last_command_retries{5}; - uint32_t _last_command_retries = 0; - std::string _last_path{}; - uint16_t _seq_number = 0; - std::ifstream _ifstream{}; - OfstreamWithPath _ofstream{}; - bool _session_valid = false; uint8_t _session = 0; - ServerResult _session_result = ServerResult::SUCCESS; - uint32_t _bytes_transferred = 0; - uint32_t _file_size = 0; - std::vector _curr_directory_list{}; + uint8_t _network_id = 0; - ResultCallback _curr_op_result_callback{}; - // _curr_op_progress_callback is used for download_callback_t as well as upload_callback_t - static_assert( - std::is_same::value, "callback types don't match"); - DownloadCallback _curr_op_progress_callback{}; - int _last_progress_percentage{-1}; - - ListDirectoryCallback _curr_dir_items_result_callback{}; - - file_crc32_ResultCallback _current_crc32_result_callback{}; - - void _calc_file_crc32_async(const std::string& path, file_crc32_ResultCallback callback); - ClientResult _calc_local_file_crc32(const std::string& path, uint32_t& csum); - - void _process_ack(PayloadHeader* payload); - void _process_nak(PayloadHeader* payload); - void _process_nak(ServerResult result); - static ClientResult _translate(ServerResult result); - void _call_op_result_callback(ServerResult result); - void _call_op_progress_callback(uint32_t bytes_written, uint32_t total_bytes); - void _call_dir_items_result_callback(ServerResult result, std::vector list); - void _call_crc32_result_callback(ServerResult result, uint32_t crc32); - void _generic_command_async( - Opcode opcode, uint32_t offset, const std::string& path, ResultCallback callback); - void _read(); - void _write(); - void _end_read_session(bool delete_file = false); - void _end_write_session(); - void _terminate_session(); - void _send_mavlink_ftp_message(const PayloadHeader& payload); - - void _command_timeout(); - void _reset_timer(); - void _stop_timer(); - void _list_directory(uint32_t offset); - uint8_t _get_target_component_id(); - - // prepend a root directory to each file/dir access to avoid enumerating the full FS tree - std::string _root_dir{"."}; - - bool _last_reply_valid = false; - uint16_t _last_reply_seq = 0; - mavlink_message_t _last_reply{}; + void* _timeout_cookie = nullptr; - void process_mavlink_ftp_message(const mavlink_message_t& msg); + LockedQueue _work_queue{}; - std::string _data_as_string(PayloadHeader* payload); - std::string _get_path(PayloadHeader* payload); - std::string _get_path(const std::string& payload_path); - std::string _get_rel_path(const std::string& path); - - ServerResult _work_list(PayloadHeader* payload, bool list_hidden = false); - ServerResult _work_open(PayloadHeader* payload, int oflag); - ServerResult _work_read(PayloadHeader* payload); - ServerResult _work_burst(PayloadHeader* payload); - ServerResult _work_write(PayloadHeader* payload); - ServerResult _work_terminate(PayloadHeader* payload); - ServerResult _work_reset(PayloadHeader* payload); - ServerResult _work_remove_directory(PayloadHeader* payload); - ServerResult _work_create_directory(PayloadHeader* payload); - ServerResult _work_remove_file(PayloadHeader* payload); - ServerResult _work_rename(PayloadHeader* payload); - ServerResult _work_calc_file_CRC32(PayloadHeader* payload); - - std::mutex _tmp_files_mutex{}; - std::unordered_map _tmp_files{}; - std::string _tmp_dir{}; + bool _debugging{false}; }; } // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_ftp_server.cpp b/src/mavsdk/core/mavlink_ftp_server.cpp new file mode 100644 index 0000000000..fbb41fe75a --- /dev/null +++ b/src/mavsdk/core/mavlink_ftp_server.cpp @@ -0,0 +1,1192 @@ +#include +#include +#include +#include + +#include "mavlink_ftp_server.h" +#include "server_component_impl.h" +#include "unused.h" +#include "crc32.h" + +namespace mavsdk { + +namespace fs = std::filesystem; + +MavlinkFtpServer::MavlinkFtpServer(ServerComponentImpl& server_component_impl) : + _server_component_impl(server_component_impl) +{ + if (const char* env_p = std::getenv("MAVSDK_FTP_DEBUGGING")) { + if (std::string(env_p) == "1") { + LogDebug() << "Ftp debugging is on."; + _debugging = true; + } + } + + _server_component_impl.register_mavlink_message_handler( + MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, + [this](const mavlink_message_t& message) { process_mavlink_ftp_message(message); }, + this); +} + +void MavlinkFtpServer::process_mavlink_ftp_message(const mavlink_message_t& msg) +{ + // TODO: implement stream sending + bool stream_send = false; + UNUSED(stream_send); + + mavlink_file_transfer_protocol_t ftp_req; + mavlink_msg_file_transfer_protocol_decode(&msg, &ftp_req); + + if (_debugging) { + LogDebug() << "Processing FTP message to target compid: " + << std::to_string(ftp_req.target_component) << ", our compid: " + << std::to_string(_server_component_impl.get_own_component_id()); + } + + if (ftp_req.target_system != 0 && + ftp_req.target_system != _server_component_impl.get_own_system_id()) { + LogWarn() << "wrong sysid!"; + return; + } + + if (ftp_req.target_component != 0 && + ftp_req.target_component != _server_component_impl.get_own_component_id()) { + LogWarn() << "wrong compid!"; + return; + } + + const PayloadHeader& payload = *reinterpret_cast(&ftp_req.payload[0]); + + // Basic sanity check: validate length before use. + if (payload.size > max_data_length) { + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + response.opcode = Opcode::RSP_NAK; + response.data[0] = ServerResult::ERR_INVALID_DATA_SIZE; + response.size = 1; + _send_mavlink_ftp_message(response); + + } else { + if (_debugging) { + LogDebug() << "FTP opcode: " << (int)payload.opcode << ", size: " << (int)payload.size + << ", offset: " << (int)payload.offset << ", seq: " << payload.seq_number; + } + + _target_system_id = msg.sysid; + _target_component_id = msg.compid; + + switch (payload.opcode) { + case Opcode::CMD_NONE: + if (_debugging) { + LogDebug() << "OPC:CMD_NONE"; + } + break; + + case Opcode::CMD_TERMINATE_SESSION: + if (_debugging) { + LogDebug() << "OPC:CMD_TERMINATE_SESSION"; + } + _work_terminate(payload); + break; + + case Opcode::CMD_RESET_SESSIONS: + if (_debugging) { + LogDebug() << "OPC:CMD_RESET_SESSIONS"; + } + _work_reset(payload); + break; + + case Opcode::CMD_LIST_DIRECTORY: + if (_debugging) { + LogDebug() << "OPC:CMD_LIST_DIRECTORY"; + } + _work_list(payload); + break; + + case Opcode::CMD_OPEN_FILE_RO: + if (_debugging) { + LogDebug() << "OPC:CMD_OPEN_FILE_RO"; + } + _work_open_file_readonly(payload); + break; + + case Opcode::CMD_CREATE_FILE: + if (_debugging) { + LogDebug() << "OPC:CMD_CREATE_FILE"; + } + _work_create_file(payload); + break; + + case Opcode::CMD_OPEN_FILE_WO: + if (_debugging) { + LogDebug() << "OPC:CMD_OPEN_FILE_WO"; + } + _work_open_file_writeonly(payload); + break; + + case Opcode::CMD_READ_FILE: + if (_debugging) { + LogDebug() << "OPC:CMD_READ_FILE"; + } + _work_read(payload); + break; + + case Opcode::CMD_BURST_READ_FILE: + if (_debugging) { + LogDebug() << "OPC:CMD_BURST_READ_FILE"; + } + _work_burst(payload); + break; + + case Opcode::CMD_WRITE_FILE: + if (_debugging) { + LogDebug() << "OPC:CMD_WRITE_FILE"; + } + _work_write(payload); + break; + + case Opcode::CMD_REMOVE_FILE: + if (_debugging) { + LogDebug() << "OPC:CMD_REMOVE_FILE"; + } + _work_remove_file(payload); + break; + + case Opcode::CMD_RENAME: + if (_debugging) { + LogDebug() << "OPC:CMD_RENAME"; + } + _work_rename(payload); + break; + + case Opcode::CMD_CREATE_DIRECTORY: + if (_debugging) { + LogDebug() << "OPC:CMD_CREATE_DIRECTORY"; + } + _work_create_directory(payload); + break; + + case Opcode::CMD_REMOVE_DIRECTORY: + if (_debugging) { + LogDebug() << "OPC:CMD_REMOVE_DIRECTORY"; + } + _work_remove_directory(payload); + break; + + case Opcode::CMD_CALC_FILE_CRC32: + if (_debugging) { + LogDebug() << "OPC:CMD_CALC_FILE_CRC32"; + } + _work_calc_file_CRC32(payload); + break; + + default: + // Not for us, ignore it. + return; + } + } +} + +MavlinkFtpServer::~MavlinkFtpServer() +{ + _server_component_impl.unregister_all_mavlink_message_handlers(this); + + std::lock_guard lock(_mutex); + _reset(); +} + +void MavlinkFtpServer::_send_mavlink_ftp_message(const PayloadHeader& payload) +{ + if (uint8_t(payload.opcode) == 0) { + abort(); + } + + _server_component_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message; + mavlink_msg_file_transfer_protocol_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &message, + _network_id, + _target_system_id, + _target_component_id, + reinterpret_cast(&payload)); + return message; + }); +} + +std::string MavlinkFtpServer::_data_as_string(const PayloadHeader& payload, size_t entry) +{ + size_t start = 0; + size_t end = 0; + std::string result; + + for (int i = entry; i >= 0; --i) { + start = end; + end += + strnlen(reinterpret_cast(&payload.data[start]), max_data_length - start) + + 1; + } + + result.resize(end - start); + std::memcpy(result.data(), &payload.data[start], end - start); + + return result; +} + +std::variant +MavlinkFtpServer::_path_from_payload(const PayloadHeader& payload, size_t entry) +{ + // Requires lock + + auto data = _data_as_string(payload, entry); + return _path_from_string(data); +} + +std::variant +MavlinkFtpServer::_path_from_string(const std::string& payload_path) +{ + // Requires lock + + // No permission whatsoever if the root dir is not set. + if (_root_dir.empty()) { + return ServerResult::ERR_FAIL; + } + + // Take a copy before we mess with it. + auto temp_path = payload_path; + + // We strip leading slashes (like absolute paths). + if (temp_path.size() >= 1 && temp_path[0] == '/') { + temp_path = temp_path.substr(1, temp_path.size()); + } + + fs::path combined_path = (fs::path(_root_dir) / temp_path).lexically_normal(); + + // Check whether the combined path is inside the root dir. + // From: https://stackoverflow.com/a/61125335/8548472 + auto ret = std::mismatch(_root_dir.begin(), _root_dir.end(), combined_path.string().begin()); + if (ret.first != _root_dir.end()) { + LogWarn() << "Not inside root dir: " << combined_path.string() + << ", root dir: " << _root_dir; + return ServerResult::ERR_FAIL; + } + + return combined_path.string(); +} + +void MavlinkFtpServer::set_root_directory(const std::string& root_dir) +{ + std::lock_guard lock(_mutex); + + std::error_code ignored; + _root_dir = fs::canonical(fs::path(root_dir), ignored).string(); + if (_debugging) { + LogDebug() << "Set root dir to: " << _root_dir; + } +} + +void MavlinkFtpServer::_work_list(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + fs::path path = std::get(maybe_path); + + uint8_t offset = 0; + + // Move to the requested offset + uint32_t requested_offset = payload.offset; + + std::error_code ec; + if (!fs::exists(path, ec)) { + LogWarn() << "FTP: can't open path " << path; + // this is not an FTP error, abort directory by simulating eof + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + + if (_debugging) { + LogDebug() << "Opening path: " << path.string(); + } + + for (const auto& entry : fs::directory_iterator(fs::canonical(path))) { + if (requested_offset > 0) { + requested_offset--; + continue; + } + const auto name = entry.path().filename(); + + std::string payload_str; + + const auto is_regular_file = entry.is_regular_file(ec); + if (ec) { + LogWarn() << "Could not determine whether '" << entry.path().string() + << "' is a file: " << ec.message(); + continue; + } + + const auto is_directory = entry.is_directory(ec); + if (ec) { + LogWarn() << "Could not determine whether '" << entry.path().string() + << "' is a directory: " << ec.message(); + continue; + } + + if (is_regular_file) { + const auto filesize = fs::file_size(entry.path(), ec); + if (ec) { + LogWarn() << "Could not get file size of '" << entry.path().string() + << "': " << ec.message(); + continue; + } + + if (_debugging) { + LogDebug() << "Found file: " << name.string() << ", size: " << filesize << " bytes"; + } + + payload_str += 'F'; + payload_str += name.string(); + payload_str += '\t'; + payload_str += std::to_string(filesize); + + } else if (is_directory) { + if (_debugging) { + LogDebug() << "Found directory: " << name.string(); + } + + payload_str += 'D'; + payload_str += name.string(); + + } else { + // Ignore all other types. + continue; + } + + auto required_len = payload_str.length() + 1; + + // Do we have room for the dir entry and the null terminator? + if (offset + required_len > max_data_length) { + break; + } + + std::memcpy(&response.data[offset], payload_str.c_str(), required_len); + + offset += static_cast(required_len); + } + + if (offset == 0) { + // We are done and need to respond with EOF. + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_EOF; + + } else { + response.opcode = Opcode::RSP_ACK; + response.size = offset; + } + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_open_file_readonly(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + if (_session_info.ifstream.is_open()) { + _reset(); + } + + std::string path; + { + std::lock_guard tmp_lock(_tmp_files_mutex); + const auto it = _tmp_files.find(_data_as_string(payload)); + if (it != _tmp_files.end()) { + path = it->second; + } else { + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + path = std::get(maybe_path); + } + } + + if (_debugging) { + LogInfo() << "Finding " << path << " in " << _root_dir; + } + if (path.rfind(_root_dir, 0) != 0) { + LogWarn() << "FTP: invalid path " << path; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + _send_mavlink_ftp_message(response); + return; + } + + if (_debugging) { + LogDebug() << "Going to open readonly: " << path; + } + + std::error_code ec; + if (!fs::exists(path, ec)) { + LogErr() << "FTP: Open failed - file doesn't exist"; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + + auto file_size = static_cast(fs::file_size(path, ec)); + if (ec) { + LogErr() << "Could not determine file size of '" << path << "': " << ec.message(); + return; + } + + if (_debugging) { + LogDebug() << "Determined filesize to be: " << file_size << " bytes"; + } + + std::ifstream ifstream; + ifstream.open(path, std::ios::in | std::ios::binary); + + if (!ifstream.is_open()) { + LogWarn() << "FTP: Open failed"; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + _send_mavlink_ftp_message(response); + return; + } + + _session_info.ifstream = std::move(ifstream); + _session_info.file_size = file_size; + + response.opcode = Opcode::RSP_ACK; + response.session = 0; + response.seq_number = payload.seq_number + 1; + response.size = sizeof(uint32_t); + std::memcpy(response.data, &file_size, response.size); + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_open_file_writeonly(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + + if (_session_info.ofstream.is_open()) { + _reset(); + } + + std::string path; + { + std::lock_guard tmp_lock(_tmp_files_mutex); + const auto it = _tmp_files.find(_data_as_string(payload)); + if (it != _tmp_files.end()) { + path = it->second; + } else { + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + path = std::get(maybe_path); + } + } + + if (path.empty()) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + + if (_debugging) { + LogDebug() << "Finding " << path << " in " << _root_dir; + } + if (path.rfind(_root_dir, 0) != 0) { + LogWarn() << "FTP: invalid path " << path; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + _send_mavlink_ftp_message(response); + return; + } + + if (_debugging) { + LogDebug() << "Going to open writeonly: " << path; + } + + // fail only if requested open for read + std::error_code ec; + if (!fs::exists(path, ec)) { + LogWarn() << "FTP: Open failed - file not found"; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + + auto file_size = static_cast(fs::file_size(path, ec)); + if (ec) { + LogErr() << "Could not determine file size of '" << path << "': " << ec.message(); + return; + } + + if (_debugging) { + LogDebug() << "Determined filesize to be: " << file_size << " bytes"; + } + + std::ofstream ofstream; + ofstream.open(path, std::ios::out | std::ios::binary); + + if (!ofstream.is_open()) { + LogWarn() << "FTP: Open failed"; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + _send_mavlink_ftp_message(response); + return; + } + + _session_info.ofstream = std::move(ofstream); + _session_info.file_size = file_size; + + response.opcode = Opcode::RSP_ACK; + response.session = 0; + response.size = sizeof(uint32_t); + std::memcpy(response.data, &file_size, response.size); + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_create_file(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + if (_session_info.ofstream.is_open()) { + _reset(); + } + + std::string path; + { + std::lock_guard tmp_lock(_tmp_files_mutex); + const auto it = _tmp_files.find(_data_as_string(payload)); + if (it != _tmp_files.end()) { + path = it->second; + } else { + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + path = std::get(maybe_path); + } + } + + if (path.empty()) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + + if (_debugging) { + LogInfo() << "Finding " << path << " in " << _root_dir; + } + if (path.rfind(_root_dir, 0) != 0) { + LogWarn() << "FTP: invalid path " << path; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + _send_mavlink_ftp_message(response); + return; + } + + if (_debugging) { + LogDebug() << "Creating file: " << path; + } + + std::ofstream ofstream; + ofstream.open(path, std::ios::out | std::ios::binary); + + if (!ofstream.is_open()) { + LogWarn() << "FTP: Open failed"; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + _send_mavlink_ftp_message(response); + return; + } + + _session_info.ofstream = std::move(ofstream); + _session_info.file_size = 0; + + response.session = 0; + response.size = 0; + response.opcode = Opcode::RSP_ACK; + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_read(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + if (payload.session != 0 || !_session_info.ifstream.is_open()) { + _reset(); + } + + // We have to test seek past EOF ourselves, lseek will allow seek past EOF + if (payload.offset >= _session_info.file_size) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_EOF; + if (_debugging) { + LogDebug() << "Reached EOF reading"; + } + _send_mavlink_ftp_message(response); + return; + } + + _session_info.ifstream.seekg(payload.offset); + if (_session_info.ifstream.fail()) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + LogWarn() << "Seek failed"; + _send_mavlink_ftp_message(response); + return; + } + + _session_info.ifstream.read(reinterpret_cast(response.data), payload.size); + + if (_session_info.ifstream.fail()) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + LogWarn() << "Read failed"; + _send_mavlink_ftp_message(response); + return; + } + + const uint32_t bytes_read = _session_info.ifstream.gcount(); + + response.size = bytes_read; + response.opcode = Opcode::RSP_ACK; + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_burst(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + if (payload.session != 0 || !_session_info.ifstream.is_open()) { + _reset(); + } + + // We have to test seek past EOF ourselves, lseek will allow seek past EOF + if (payload.offset >= _session_info.file_size) { + response.seq_number = payload.seq_number + 1; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_EOF; + if (_debugging) { + LogDebug() << "Reached EOF reading"; + } + _send_mavlink_ftp_message(response); + return; + } + + if (_debugging) { + LogDebug() << "Seek to " << payload.offset; + } + _session_info.ifstream.seekg(payload.offset); + if (_session_info.ifstream.fail()) { + response.seq_number = payload.seq_number + 1; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + LogErr() << "Seek failed"; + _send_mavlink_ftp_message(response); + return; + } + + _session_info.burst_offset = payload.offset; + + if (payload.size != 4) { + response.seq_number = payload.seq_number + 1; + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_INVALID_DATA_SIZE; + LogErr() << "Burst size invalid"; + _send_mavlink_ftp_message(response); + return; + } + + uint32_t burst_size; + std::memcpy(&burst_size, &payload.data, payload.size); + _session_info.burst_end = _session_info.burst_offset + burst_size; + + _burst_seq = payload.seq_number + 1; + + // Schedule sending out burst messages. + // Use some arbitrary "fast" rate: 100 packets per second + _server_component_impl.add_call_every( + [this]() { _send_burst_packet(); }, 0.01f, &_burst_call_every_cookie); + + // Don't send response as that's done in the call every burst call above. +} + +void MavlinkFtpServer::_send_burst_packet() +{ + std::lock_guard lock(_mutex); + if (!_session_info.ifstream.is_open()) { + _reset(); + } + + PayloadHeader burst_packet{}; + burst_packet.req_opcode = Opcode::CMD_BURST_READ_FILE; + burst_packet.seq_number = _burst_seq++; + + _make_burst_packet(burst_packet); + + _send_mavlink_ftp_message(burst_packet); + + if (burst_packet.burst_complete == 1) { + if (_burst_call_every_cookie != nullptr) { + _server_component_impl.remove_call_every(_burst_call_every_cookie); + _burst_call_every_cookie = nullptr; + } + } +} + +void MavlinkFtpServer::_make_burst_packet(PayloadHeader& packet) +{ + uint32_t bytes_to_read = std::min( + static_cast(max_data_length), + _session_info.burst_end - _session_info.burst_offset); + + if (_debugging) { + LogDebug() << "Burst read of " << bytes_to_read << " bytes"; + } + _session_info.ifstream.read(reinterpret_cast(packet.data), bytes_to_read); + + if (_session_info.ifstream.fail()) { + packet.opcode = Opcode::RSP_NAK; + packet.size = 1; + packet.data[0] = ServerResult::ERR_FAIL; + LogWarn() << "Burst read failed"; + return; + } + + const uint32_t bytes_read = _session_info.ifstream.gcount(); + packet.size = bytes_read; + packet.opcode = Opcode::RSP_ACK; + + packet.offset = _session_info.burst_offset; + _session_info.burst_offset += bytes_read; + + if (_session_info.burst_offset == _session_info.burst_end) { + // Last read, we are done for this burst. + packet.burst_complete = 1; + if (_debugging) { + LogDebug() << "Burst complete"; + } + } +} + +void MavlinkFtpServer::_work_write(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + if (payload.session != 0 && !_session_info.ofstream.is_open()) { + _reset(); + } + + _session_info.ofstream.seekp(payload.offset); + if (_session_info.ifstream.fail()) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + LogWarn() << "Seek failed"; + _send_mavlink_ftp_message(response); + return; + } + + _session_info.ofstream.write(reinterpret_cast(payload.data), payload.size); + if (_session_info.ofstream.fail()) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + LogWarn() << "Write failed"; + _send_mavlink_ftp_message(response); + return; + } + + response.opcode = Opcode::RSP_ACK; + response.size = sizeof(uint32_t); + std::memcpy(response.data, &payload.size, response.size); + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_terminate(const PayloadHeader& payload) +{ + { + std::lock_guard lock(_mutex); + _reset(); + } + + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + response.opcode = Opcode::RSP_ACK; + response.size = 0; + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_reset() +{ + // requires lock + if (_session_info.ifstream.is_open()) { + _session_info.ifstream.close(); + } + + if (_session_info.ofstream.is_open()) { + _session_info.ofstream.close(); + } + + if (_burst_call_every_cookie != nullptr) { + _server_component_impl.remove_call_every(_burst_call_every_cookie); + _burst_call_every_cookie = nullptr; + } +} + +void MavlinkFtpServer::_work_reset(const PayloadHeader& payload) +{ + { + std::lock_guard lock(_mutex); + _reset(); + } + + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + response.opcode = Opcode::RSP_ACK; + response.size = 0; + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_remove_directory(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + fs::path path = std::get(maybe_path); + + std::error_code ec; + if (!fs::exists(path, ec)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + if (fs::remove(path, ec)) { + response.opcode = Opcode::RSP_ACK; + response.size = 0; + } else { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + } + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_create_directory(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + auto path = std::get(maybe_path); + + std::error_code ec; + if (fs::exists(path, ec)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_EXISTS; + _send_mavlink_ftp_message(response); + return; + } + + if (fs::create_directory(path, ec)) { + response.opcode = Opcode::RSP_ACK; + } else { + response.opcode = Opcode::RSP_NAK; + response.size = 2; + response.data[0] = ServerResult::ERR_FAIL_ERRNO; + response.data[1] = static_cast(ec.value()); + } + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_remove_file(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + auto path = std::get(maybe_path); + + std::error_code ec; + if (!fs::exists(path, ec)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + if (fs::remove(path, ec)) { + response.opcode = Opcode::RSP_ACK; + } else { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + } + + _send_mavlink_ftp_message(response); +} + +void MavlinkFtpServer::_work_rename(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + + auto maybe_old_name = _path_from_payload(payload, 0); + + if (std::holds_alternative(maybe_old_name)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_old_name); + _send_mavlink_ftp_message(response); + return; + } + + auto old_name = std::get(maybe_old_name); + + auto maybe_new_name = _path_from_payload(payload, 1); + + if (std::holds_alternative(maybe_new_name)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_new_name); + _send_mavlink_ftp_message(response); + return; + } + + auto new_name = std::get(maybe_new_name); + + if (_debugging) { + LogDebug() << "Rename from old_name " << old_name << " to " << new_name; + } + + std::error_code ec; + if (!fs::exists(old_name, ec)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + + fs::rename(old_name, new_name, ec); + if (!ec) { + response.opcode = Opcode::RSP_ACK; + } else { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL; + } + + _send_mavlink_ftp_message(response); +} + +MavlinkFtpServer::ServerResult +MavlinkFtpServer::_calc_local_file_crc32(const std::string& path, uint32_t& csum) +{ + std::error_code ec; + if (!fs::exists(path, ec)) { + return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + } + + std::ifstream ifstream; + ifstream.open(path, std::ios::in | std::ios::binary); + + if (!ifstream.is_open()) { + return ServerResult::ERR_FILE_IO_ERROR; + } + + // Read whole file in buffer size chunks + Crc32 checksum; + char buffer[18392]; + do { + ifstream.read(buffer, sizeof(buffer)); + + if (ifstream.fail() && !ifstream.eof()) { + ifstream.close(); + return ServerResult::ERR_FILE_IO_ERROR; + } + + auto bytes_read = ifstream.gcount(); + checksum.add((uint8_t*)buffer, bytes_read); + + } while (!ifstream.eof()); + + ifstream.close(); + + csum = checksum.get(); + + return ServerResult::SUCCESS; +} + +void MavlinkFtpServer::_work_calc_file_CRC32(const PayloadHeader& payload) +{ + auto response = PayloadHeader{}; + response.seq_number = payload.seq_number + 1; + response.req_opcode = payload.opcode; + + std::lock_guard lock(_mutex); + + auto maybe_path = _path_from_payload(payload); + if (std::holds_alternative(maybe_path)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = std::get(maybe_path); + _send_mavlink_ftp_message(response); + return; + } + + auto path = std::get(maybe_path); + + std::error_code ec; + if (!fs::exists(path, ec)) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; + _send_mavlink_ftp_message(response); + return; + } + + uint32_t checksum; + ServerResult res = _calc_local_file_crc32(path, checksum); + if (res != ServerResult::SUCCESS) { + response.opcode = Opcode::RSP_NAK; + response.size = 1; + response.data[0] = res; + _send_mavlink_ftp_message(response); + return; + } + + response.opcode = Opcode::RSP_ACK; + response.size = sizeof(uint32_t); + std::memcpy(response.data, &checksum, response.size); + + _send_mavlink_ftp_message(response); +} + +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_ftp_server.h b/src/mavsdk/core/mavlink_ftp_server.h new file mode 100644 index 0000000000..ba917d533e --- /dev/null +++ b/src/mavsdk/core/mavlink_ftp_server.h @@ -0,0 +1,163 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "mavlink_include.h" + +// As found in +// https://stackoverflow.com/questions/1537964#answer-3312896 +#ifdef _MSC_VER // MSVC +#define PACK(__Declaration__) __pragma(pack(push, 1)) __Declaration__ __pragma(pack(pop)) +#else +#define PACK(__Declaration__) __Declaration__ __attribute__((__packed__)) +#endif + +namespace mavsdk { + +class ServerComponentImpl; + +class MavlinkFtpServer { +public: + explicit MavlinkFtpServer(ServerComponentImpl& server_component_impl); + ~MavlinkFtpServer(); + + struct ProgressData { + uint32_t bytes_transferred{}; /**< @brief The number of bytes already transferred. */ + uint32_t total_bytes{}; /**< @brief The total bytes to transfer. */ + }; + + void set_root_directory(const std::string& root_dir); + +private: + ServerComponentImpl& _server_component_impl; + + /// @brief Possible server results returned for requests. + enum ServerResult : uint8_t { + SUCCESS, + ERR_FAIL, ///< Unknown failure + ERR_FAIL_ERRNO, ///< Command failed, errno sent back in PayloadHeader.data[1] + ERR_INVALID_DATA_SIZE, ///< PayloadHeader.size is invalid + ERR_INVALID_SESSION, ///< Session is not currently open + ERR_NO_SESSIONS_AVAILABLE, ///< All available Sessions in use + ERR_EOF, ///< Offset past end of file for List and Read commands + ERR_UNKOWN_COMMAND, ///< Unknown command opcode + ERR_FAIL_FILE_EXISTS, ///< File exists already + ERR_FAIL_FILE_PROTECTED, ///< File is write protected + ERR_FAIL_FILE_DOES_NOT_EXIST, ///< File does not exist + + // These error codes are returned to client without contacting the server + ERR_TIMEOUT = 200, ///< Timeout + ERR_FILE_IO_ERROR, ///< File IO operation error + }; + + /// @brief Command opcodes + enum class Opcode : uint8_t { + CMD_NONE, ///< ignored, always acked + CMD_TERMINATE_SESSION, ///< Terminates open Read session + CMD_RESET_SESSIONS, ///< Terminates all open Read sessions + CMD_LIST_DIRECTORY, ///< List files in from + CMD_OPEN_FILE_RO, ///< Opens file at for reading, returns + CMD_READ_FILE, ///< Reads bytes from in + CMD_CREATE_FILE, ///< Creates file at for writing, returns + CMD_WRITE_FILE, ///< Writes bytes to in + CMD_REMOVE_FILE, ///< Remove file at + CMD_CREATE_DIRECTORY, ///< Creates directory at + CMD_REMOVE_DIRECTORY, ///< Removes Directory at , must be empty + CMD_OPEN_FILE_WO, ///< Opens file at for writing, returns + CMD_TRUNCATE_FILE, ///< Truncate file at to length + CMD_RENAME, ///< Rename to + CMD_CALC_FILE_CRC32, ///< Calculate CRC32 for file at + CMD_BURST_READ_FILE, ///< Burst download session file + + RSP_ACK = 128, ///< Ack response + RSP_NAK ///< Nak response + }; + + /// @brief Maximum data size in RequestHeader::data + static constexpr uint8_t max_data_length = 239; + + /// @brief This is the payload which is in mavlink_file_transfer_protocol_t.payload. + /// This needs to be packed, because it's typecasted from + /// mavlink_file_transfer_protocol_t.payload, which starts at a 3 byte offset, causing an + /// unaligned access to seq_number and offset + PACK(struct PayloadHeader { + uint16_t seq_number; ///< sequence number for message + uint8_t session; ///< Session id for read and write commands + Opcode opcode; ///< Command opcode + uint8_t size; ///< Size of data + Opcode req_opcode; ///< Request opcode returned in RSP_ACK, RSP_NAK message + uint8_t burst_complete; ///< Only used if req_opcode=CMD_BURST_READ_FILE - 1: set of burst + ///< packets complete, 0: More burst packets coming. + uint8_t padding; ///< 32 bit alignment padding + uint32_t offset; ///< Offsets for List and Read commands + uint8_t data[max_data_length]; ///< command data, varies by Opcode + }); + + static_assert( + sizeof(PayloadHeader) == sizeof(mavlink_file_transfer_protocol_t::payload), + "PayloadHeader size is incorrect."); + + ServerResult _calc_local_file_crc32(const std::string& path, uint32_t& csum); + + void _send_mavlink_ftp_message(const PayloadHeader& payload); + + void _reset(); + + void process_mavlink_ftp_message(const mavlink_message_t& msg); + + std::string _data_as_string(const PayloadHeader& payload, size_t entry = 0); + std::variant + _path_from_payload(const PayloadHeader& payload, size_t entry = 0); + std::variant _path_from_string(const std::string& payload_path); + + void _work_list(const PayloadHeader& payload); + void _work_open_file_readonly(const PayloadHeader& payload); + void _work_open_file_writeonly(const PayloadHeader& payload); + void _work_create_file(const PayloadHeader& payload); + void _work_read(const PayloadHeader& payload); + void _work_burst(const PayloadHeader& payload); + void _work_write(const PayloadHeader& payload); + void _work_terminate(const PayloadHeader& payload); + void _work_reset(const PayloadHeader& payload); + void _work_remove_directory(const PayloadHeader& payload); + void _work_create_directory(const PayloadHeader& payload); + void _work_remove_file(const PayloadHeader& payload); + void _work_rename(const PayloadHeader& payload); + void _work_calc_file_CRC32(const PayloadHeader& payload); + + void _send_burst_packet(); + void _make_burst_packet(PayloadHeader& packet); + void* _burst_call_every_cookie{nullptr}; + + std::mutex _mutex{}; + struct SessionInfo { + uint32_t file_size{0}; + uint32_t burst_offset{0}; + uint32_t burst_end{0}; + std::ifstream ifstream; + std::ofstream ofstream; + } _session_info{}; + + uint8_t _network_id = 0; + uint8_t _target_system_id = 0; + uint8_t _target_component_id = 0; + std::string _root_dir{}; + + std::mutex _tmp_files_mutex{}; + std::unordered_map _tmp_files{}; + std::string _tmp_dir{}; + + uint16_t _burst_seq = 0; + + bool _debugging{false}; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_parameter_cache.cpp b/src/mavsdk/core/mavlink_parameter_cache.cpp index bef3321db5..e580ad709b 100644 --- a/src/mavsdk/core/mavlink_parameter_cache.cpp +++ b/src/mavsdk/core/mavlink_parameter_cache.cpp @@ -11,7 +11,8 @@ MavlinkParameterCache::add_new_param(const std::string& param_id, ParamValue val return AddNewParamResult::AlreadyExists; } - if (_all_params.size() + 1 > std::numeric_limits::max()) { + if (static_cast(_all_params.size() + 1) > + static_cast(std::numeric_limits::max())) { return AddNewParamResult::TooManyParams; } diff --git a/src/mavsdk/core/server_component.cpp b/src/mavsdk/core/server_component.cpp index bfb52a2f73..7a773ee429 100644 --- a/src/mavsdk/core/server_component.cpp +++ b/src/mavsdk/core/server_component.cpp @@ -7,4 +7,9 @@ ServerComponent::ServerComponent(MavsdkImpl& mavsdk_impl, uint8_t component_id) _impl(std::make_unique(mavsdk_impl, component_id)) {} +uint8_t ServerComponent::component_id() const +{ + return _impl->get_own_component_id(); +} + } // namespace mavsdk diff --git a/src/mavsdk/core/server_component_impl.cpp b/src/mavsdk/core/server_component_impl.cpp index 7805c212d4..47addb51b7 100644 --- a/src/mavsdk/core/server_component_impl.cpp +++ b/src/mavsdk/core/server_component_impl.cpp @@ -15,7 +15,8 @@ ServerComponentImpl::ServerComponentImpl(MavsdkImpl& mavsdk_impl, uint8_t compon mavsdk_impl.timeout_handler, [this]() { return _mavsdk_impl.timeout_s(); }), _mavlink_parameter_server(_our_sender, mavsdk_impl.mavlink_message_handler), - _mavlink_request_message_handler(mavsdk_impl, *this, _mavlink_command_receiver) + _mavlink_request_message_handler(mavsdk_impl, *this, _mavlink_command_receiver), + _mavlink_ftp_server(*this) { if (!MavlinkChannels::Instance().checkout_free_channel(_channel)) { // We use a default of channel 0 which will still work but not track diff --git a/src/mavsdk/core/server_component_impl.h b/src/mavsdk/core/server_component_impl.h index f1a628ca5a..f151f7b4f4 100644 --- a/src/mavsdk/core/server_component_impl.h +++ b/src/mavsdk/core/server_component_impl.h @@ -7,6 +7,7 @@ #include "mavlink_mission_transfer.h" #include "mavlink_parameter_server.h" #include "mavlink_request_message_handler.h" +#include "mavlink_ftp_server.h" #include "mavsdk_time.h" #include "flight_mode.h" #include "log.h" @@ -147,6 +148,7 @@ class ServerComponentImpl { { return _mavlink_request_message_handler; } + MavlinkFtpServer& mavlink_ftp_server() { return _mavlink_ftp_server; } void do_work(); @@ -171,6 +173,7 @@ class ServerComponentImpl { MavlinkMissionTransfer _mission_transfer; MavlinkParameterServer _mavlink_parameter_server; MavlinkRequestMessageHandler _mavlink_request_message_handler; + MavlinkFtpServer _mavlink_ftp_server; }; } // namespace mavsdk diff --git a/src/mavsdk/core/system_impl.cpp b/src/mavsdk/core/system_impl.cpp index 3cd2311ecb..1d7e8cd438 100644 --- a/src/mavsdk/core/system_impl.cpp +++ b/src/mavsdk/core/system_impl.cpp @@ -33,7 +33,7 @@ SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) : [this]() { return timeout_s(); }), _request_message( *this, _command_sender, _mavsdk_impl.mavlink_message_handler, _mavsdk_impl.timeout_handler), - _mavlink_ftp(*this) + _mavlink_ftp_client(*this) { _system_thread = new std::thread(&SystemImpl::system_thread, this); } @@ -285,6 +285,7 @@ void SystemImpl::system_thread() _command_sender.do_work(); _timesync.do_work(); _mission_transfer.do_work(); + _mavlink_ftp_client.do_work(); if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) { if (_connected && _autopilot != Autopilot::ArduPilot) { diff --git a/src/mavsdk/core/system_impl.h b/src/mavsdk/core/system_impl.h index c64f79ccca..9a2ea7133e 100644 --- a/src/mavsdk/core/system_impl.h +++ b/src/mavsdk/core/system_impl.h @@ -8,7 +8,7 @@ #include "mavlink_parameter_client.h" #include "mavlink_command_sender.h" #include "mavlink_command_receiver.h" -#include "mavlink_ftp.h" +#include "mavlink_ftp_client.h" #include "mavlink_message_handler.h" #include "mavlink_mission_transfer.h" #include "mavlink_request_message_handler.h" @@ -285,7 +285,7 @@ class SystemImpl { MavlinkMissionTransfer& mission_transfer() { return _mission_transfer; }; - MavlinkFtp& mavlink_ftp() { return _mavlink_ftp; }; + MavlinkFtpClient& mavlink_ftp_client() { return _mavlink_ftp_client; }; RequestMessage& request_message() { return _request_message; }; @@ -394,7 +394,7 @@ class SystemImpl { MavlinkMissionTransfer _mission_transfer; RequestMessage _request_message; - MavlinkFtp _mavlink_ftp; + MavlinkFtpClient _mavlink_ftp_client; std::mutex _plugin_impls_mutex{}; std::vector _plugin_impls{}; diff --git a/src/mavsdk/core/tronkko_dirent.h b/src/mavsdk/core/tronkko_dirent.h deleted file mode 100644 index 7db3875d9e..0000000000 --- a/src/mavsdk/core/tronkko_dirent.h +++ /dev/null @@ -1,1154 +0,0 @@ -#pragma once -// Taken from: -// https://github.com/tronkko/dirent/blob/c885633e126a3a949ec0497273ec13e2c03e862c/include/dirent.h - -/* - * Dirent interface for Microsoft Visual Studio - * - * Copyright (C) 1998-2019 Toni Ronkko - * This file is part of dirent. Dirent may be freely distributed - * under the MIT license. For all details and documentation, see - * https://github.com/tronkko/dirent - */ - -/* Hide warnings about unreferenced local functions */ -#if defined(__clang__) -# pragma clang diagnostic ignored "-Wunused-function" -#elif defined(_MSC_VER) -# pragma warning(disable:4505) -#elif defined(__GNUC__) -# pragma GCC diagnostic ignored "-Wunused-function" -#endif - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* Indicates that d_type field is available in dirent structure */ -#define _DIRENT_HAVE_D_TYPE - -/* Indicates that d_namlen field is available in dirent structure */ -#define _DIRENT_HAVE_D_NAMLEN - -/* Entries missing from MSVC 6.0 */ -#if !defined(FILE_ATTRIBUTE_DEVICE) -# define FILE_ATTRIBUTE_DEVICE 0x40 -#endif - -/* File type and permission flags for stat(), general mask */ -#if !defined(S_IFMT) -# define S_IFMT _S_IFMT -#endif - -/* Directory bit */ -#if !defined(S_IFDIR) -# define S_IFDIR _S_IFDIR -#endif - -/* Character device bit */ -#if !defined(S_IFCHR) -# define S_IFCHR _S_IFCHR -#endif - -/* Pipe bit */ -#if !defined(S_IFFIFO) -# define S_IFFIFO _S_IFFIFO -#endif - -/* Regular file bit */ -#if !defined(S_IFREG) -# define S_IFREG _S_IFREG -#endif - -/* Read permission */ -#if !defined(S_IREAD) -# define S_IREAD _S_IREAD -#endif - -/* Write permission */ -#if !defined(S_IWRITE) -# define S_IWRITE _S_IWRITE -#endif - -/* Execute permission */ -#if !defined(S_IEXEC) -# define S_IEXEC _S_IEXEC -#endif - -/* Pipe */ -#if !defined(S_IFIFO) -# define S_IFIFO _S_IFIFO -#endif - -/* Block device */ -#if !defined(S_IFBLK) -# define S_IFBLK 0 -#endif - -/* Link */ -#if !defined(S_IFLNK) -# define S_IFLNK 0 -#endif - -/* Socket */ -#if !defined(S_IFSOCK) -# define S_IFSOCK 0 -#endif - -/* Read user permission */ -#if !defined(S_IRUSR) -# define S_IRUSR S_IREAD -#endif - -/* Write user permission */ -#if !defined(S_IWUSR) -# define S_IWUSR S_IWRITE -#endif - -/* Execute user permission */ -#if !defined(S_IXUSR) -# define S_IXUSR 0 -#endif - -/* Read group permission */ -#if !defined(S_IRGRP) -# define S_IRGRP 0 -#endif - -/* Write group permission */ -#if !defined(S_IWGRP) -# define S_IWGRP 0 -#endif - -/* Execute group permission */ -#if !defined(S_IXGRP) -# define S_IXGRP 0 -#endif - -/* Read others permission */ -#if !defined(S_IROTH) -# define S_IROTH 0 -#endif - -/* Write others permission */ -#if !defined(S_IWOTH) -# define S_IWOTH 0 -#endif - -/* Execute others permission */ -#if !defined(S_IXOTH) -# define S_IXOTH 0 -#endif - -/* Maximum length of file name */ -#if !defined(PATH_MAX) -# define PATH_MAX MAX_PATH -#endif -#if !defined(FILENAME_MAX) -# define FILENAME_MAX MAX_PATH -#endif -#if !defined(NAME_MAX) -# define NAME_MAX FILENAME_MAX -#endif - -/* File type flags for d_type */ -#define DT_UNKNOWN 0 -#define DT_REG S_IFREG -#define DT_DIR S_IFDIR -#define DT_FIFO S_IFIFO -#define DT_SOCK S_IFSOCK -#define DT_CHR S_IFCHR -#define DT_BLK S_IFBLK -#define DT_LNK S_IFLNK - -/* Macros for converting between st_mode and d_type */ -#define IFTODT(mode) ((mode) & S_IFMT) -#define DTTOIF(type) (type) - -/* - * File type macros. Note that block devices, sockets and links cannot be - * distinguished on Windows and the macros S_ISBLK, S_ISSOCK and S_ISLNK are - * only defined for compatibility. These macros should always return false - * on Windows. - */ -#if !defined(S_ISFIFO) -# define S_ISFIFO(mode) (((mode) & S_IFMT) == S_IFIFO) -#endif -#if !defined(S_ISDIR) -# define S_ISDIR(mode) (((mode) & S_IFMT) == S_IFDIR) -#endif -#if !defined(S_ISREG) -# define S_ISREG(mode) (((mode) & S_IFMT) == S_IFREG) -#endif -#if !defined(S_ISLNK) -# define S_ISLNK(mode) (((mode) & S_IFMT) == S_IFLNK) -#endif -#if !defined(S_ISSOCK) -# define S_ISSOCK(mode) (((mode) & S_IFMT) == S_IFSOCK) -#endif -#if !defined(S_ISCHR) -# define S_ISCHR(mode) (((mode) & S_IFMT) == S_IFCHR) -#endif -#if !defined(S_ISBLK) -# define S_ISBLK(mode) (((mode) & S_IFMT) == S_IFBLK) -#endif - -/* Return the exact length of the file name without zero terminator */ -#define _D_EXACT_NAMLEN(p) ((p)->d_namlen) - -/* Return the maximum size of a file name */ -#define _D_ALLOC_NAMLEN(p) ((PATH_MAX)+1) - - -#ifdef __cplusplus -extern "C" { -#endif - - -/* Wide-character version */ -struct _wdirent { - /* Always zero */ - long d_ino; - - /* File position within stream */ - long d_off; - - /* Structure size */ - unsigned short d_reclen; - - /* Length of name without \0 */ - size_t d_namlen; - - /* File type */ - int d_type; - - /* File name */ - wchar_t d_name[PATH_MAX+1]; -}; -typedef struct _wdirent _wdirent; - -struct _WDIR { - /* Current directory entry */ - struct _wdirent ent; - - /* Private file data */ - WIN32_FIND_DATAW data; - - /* True if data is valid */ - int cached; - - /* Win32 search handle */ - HANDLE handle; - - /* Initial directory name */ - wchar_t *patt; -}; -typedef struct _WDIR _WDIR; - -/* Multi-byte character version */ -struct dirent { - /* Always zero */ - long d_ino; - - /* File position within stream */ - long d_off; - - /* Structure size */ - unsigned short d_reclen; - - /* Length of name without \0 */ - size_t d_namlen; - - /* File type */ - int d_type; - - /* File name */ - char d_name[PATH_MAX+1]; -}; -typedef struct dirent dirent; - -struct DIR { - struct dirent ent; - struct _WDIR *wdirp; -}; -typedef struct DIR DIR; - - -/* Dirent functions */ -static DIR *opendir (const char *dirname); -static _WDIR *_wopendir (const wchar_t *dirname); - -static struct dirent *readdir (DIR *dirp); -static struct _wdirent *_wreaddir (_WDIR *dirp); - -static int readdir_r( - DIR *dirp, struct dirent *entry, struct dirent **result); -static int _wreaddir_r( - _WDIR *dirp, struct _wdirent *entry, struct _wdirent **result); - -static int closedir (DIR *dirp); -static int _wclosedir (_WDIR *dirp); - -static void rewinddir (DIR* dirp); -static void _wrewinddir (_WDIR* dirp); - -static int scandir (const char *dirname, struct dirent ***namelist, - int (*filter)(const struct dirent*), - int (*compare)(const struct dirent**, const struct dirent**)); - -static int alphasort (const struct dirent **a, const struct dirent **b); - -static int versionsort (const struct dirent **a, const struct dirent **b); - - -/* For compatibility with Symbian */ -#define wdirent _wdirent -#define WDIR _WDIR -#define wopendir _wopendir -#define wreaddir _wreaddir -#define wclosedir _wclosedir -#define wrewinddir _wrewinddir - - -/* Internal utility functions */ -static WIN32_FIND_DATAW *dirent_first (_WDIR *dirp); -static WIN32_FIND_DATAW *dirent_next (_WDIR *dirp); - -static int dirent_mbstowcs_s( - size_t *pReturnValue, - wchar_t *wcstr, - size_t sizeInWords, - const char *mbstr, - size_t count); - -static int dirent_wcstombs_s( - size_t *pReturnValue, - char *mbstr, - size_t sizeInBytes, - const wchar_t *wcstr, - size_t count); - -static void dirent_set_errno (int error); - - -/* - * Open directory stream DIRNAME for read and return a pointer to the - * internal working area that is used to retrieve individual directory - * entries. - */ -static _WDIR* -_wopendir( - const wchar_t *dirname) -{ - _WDIR *dirp; - DWORD n; - wchar_t *p; - - /* Must have directory name */ - if (dirname == NULL || dirname[0] == '\0') { - dirent_set_errno (ENOENT); - return NULL; - } - - /* Allocate new _WDIR structure */ - dirp = (_WDIR*) malloc (sizeof (struct _WDIR)); - if (!dirp) { - return NULL; - } - - /* Reset _WDIR structure */ - dirp->handle = INVALID_HANDLE_VALUE; - dirp->patt = NULL; - dirp->cached = 0; - - /* - * Compute the length of full path plus zero terminator - * - * Note that on WinRT there's no way to convert relative paths - * into absolute paths, so just assume it is an absolute path. - */ -#if WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) - /* Desktop */ - n = GetFullPathNameW (dirname, 0, NULL, NULL); -#else - /* WinRT */ - n = wcslen (dirname); -#endif - - /* Allocate room for absolute directory name and search pattern */ - dirp->patt = (wchar_t*) malloc (sizeof (wchar_t) * n + 16); - if (dirp->patt == NULL) { - goto exit_closedir; - } - - /* - * Convert relative directory name to an absolute one. This - * allows rewinddir() to function correctly even when current - * working directory is changed between opendir() and rewinddir(). - * - * Note that on WinRT there's no way to convert relative paths - * into absolute paths, so just assume it is an absolute path. - */ -#if WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) - /* Desktop */ - n = GetFullPathNameW (dirname, n, dirp->patt, NULL); - if (n <= 0) { - goto exit_closedir; - } -#else - /* WinRT */ - wcsncpy_s (dirp->patt, n+1, dirname, n); -#endif - - /* Append search pattern \* to the directory name */ - p = dirp->patt + n; - switch (p[-1]) { - case '\\': - case '/': - case ':': - /* Directory ends in path separator, e.g. c:\temp\ */ - /*NOP*/; - break; - - default: - /* Directory name doesn't end in path separator */ - *p++ = '\\'; - } - *p++ = '*'; - *p = '\0'; - - /* Open directory stream and retrieve the first entry */ - if (!dirent_first (dirp)) { - goto exit_closedir; - } - - /* Success */ - return dirp; - - /* Failure */ -exit_closedir: - _wclosedir (dirp); - return NULL; -} - -/* - * Read next directory entry. - * - * Returns pointer to static directory entry which may be overwritten by - * subsequent calls to _wreaddir(). - */ -static struct _wdirent* -_wreaddir( - _WDIR *dirp) -{ - struct _wdirent *entry; - - /* - * Read directory entry to buffer. We can safely ignore the return value - * as entry will be set to NULL in case of error. - */ - (void) _wreaddir_r (dirp, &dirp->ent, &entry); - - /* Return pointer to statically allocated directory entry */ - return entry; -} - -/* - * Read next directory entry. - * - * Returns zero on success. If end of directory stream is reached, then sets - * result to NULL and returns zero. - */ -static int -_wreaddir_r( - _WDIR *dirp, - struct _wdirent *entry, - struct _wdirent **result) -{ - WIN32_FIND_DATAW *datap; - - /* Read next directory entry */ - datap = dirent_next (dirp); - if (datap) { - size_t n; - DWORD attr; - - /* - * Copy file name as wide-character string. If the file name is too - * long to fit in to the destination buffer, then truncate file name - * to PATH_MAX characters and zero-terminate the buffer. - */ - n = 0; - while (n < PATH_MAX && datap->cFileName[n] != 0) { - entry->d_name[n] = datap->cFileName[n]; - n++; - } - entry->d_name[n] = 0; - - /* Length of file name excluding zero terminator */ - entry->d_namlen = n; - - /* File type */ - attr = datap->dwFileAttributes; - if ((attr & FILE_ATTRIBUTE_DEVICE) != 0) { - entry->d_type = DT_CHR; - } else if ((attr & FILE_ATTRIBUTE_DIRECTORY) != 0) { - entry->d_type = DT_DIR; - } else { - entry->d_type = DT_REG; - } - - /* Reset dummy fields */ - entry->d_ino = 0; - entry->d_off = 0; - entry->d_reclen = sizeof (struct _wdirent); - - /* Set result address */ - *result = entry; - - } else { - - /* Return NULL to indicate end of directory */ - *result = NULL; - - } - - return /*OK*/0; -} - -/* - * Close directory stream opened by opendir() function. This invalidates the - * DIR structure as well as any directory entry read previously by - * _wreaddir(). - */ -static int -_wclosedir( - _WDIR *dirp) -{ - int ok; - if (dirp) { - - /* Release search handle */ - if (dirp->handle != INVALID_HANDLE_VALUE) { - FindClose (dirp->handle); - } - - /* Release search pattern */ - free (dirp->patt); - - /* Release directory structure */ - free (dirp); - ok = /*success*/0; - - } else { - - /* Invalid directory stream */ - dirent_set_errno (EBADF); - ok = /*failure*/-1; - - } - return ok; -} - -/* - * Rewind directory stream such that _wreaddir() returns the very first - * file name again. - */ -static void -_wrewinddir( - _WDIR* dirp) -{ - if (dirp) { - /* Release existing search handle */ - if (dirp->handle != INVALID_HANDLE_VALUE) { - FindClose (dirp->handle); - } - - /* Open new search handle */ - dirent_first (dirp); - } -} - -/* Get first directory entry (internal) */ -static WIN32_FIND_DATAW* -dirent_first( - _WDIR *dirp) -{ - WIN32_FIND_DATAW *datap; - DWORD error; - - /* Open directory and retrieve the first entry */ - dirp->handle = FindFirstFileExW( - dirp->patt, FindExInfoStandard, &dirp->data, - FindExSearchNameMatch, NULL, 0); - if (dirp->handle != INVALID_HANDLE_VALUE) { - - /* a directory entry is now waiting in memory */ - datap = &dirp->data; - dirp->cached = 1; - - } else { - - /* Failed to open directory: no directory entry in memory */ - dirp->cached = 0; - datap = NULL; - - /* Set error code */ - error = GetLastError (); - switch (error) { - case ERROR_ACCESS_DENIED: - /* No read access to directory */ - dirent_set_errno (EACCES); - break; - - case ERROR_DIRECTORY: - /* Directory name is invalid */ - dirent_set_errno (ENOTDIR); - break; - - case ERROR_PATH_NOT_FOUND: - default: - /* Cannot find the file */ - dirent_set_errno (ENOENT); - } - - } - return datap; -} - -/* - * Get next directory entry (internal). - * - * Returns - */ -static WIN32_FIND_DATAW* -dirent_next( - _WDIR *dirp) -{ - WIN32_FIND_DATAW *p; - - /* Get next directory entry */ - if (dirp->cached != 0) { - - /* A valid directory entry already in memory */ - p = &dirp->data; - dirp->cached = 0; - - } else if (dirp->handle != INVALID_HANDLE_VALUE) { - - /* Get the next directory entry from stream */ - if (FindNextFileW (dirp->handle, &dirp->data) != FALSE) { - /* Got a file */ - p = &dirp->data; - } else { - /* The very last entry has been processed or an error occurred */ - FindClose (dirp->handle); - dirp->handle = INVALID_HANDLE_VALUE; - p = NULL; - } - - } else { - - /* End of directory stream reached */ - p = NULL; - - } - - return p; -} - -/* - * Open directory stream using plain old C-string. - */ -static DIR* -opendir( - const char *dirname) -{ - struct DIR *dirp; - - /* Must have directory name */ - if (dirname == NULL || dirname[0] == '\0') { - dirent_set_errno (ENOENT); - return NULL; - } - - /* Allocate memory for DIR structure */ - dirp = (DIR*) malloc (sizeof (struct DIR)); - if (!dirp) { - return NULL; - } - { - int error; - wchar_t wname[PATH_MAX + 1]; - size_t n; - - /* Convert directory name to wide-character string */ - error = dirent_mbstowcs_s( - &n, wname, PATH_MAX + 1, dirname, PATH_MAX + 1); - if (error) { - /* - * Cannot convert file name to wide-character string. This - * occurs if the string contains invalid multi-byte sequences or - * the output buffer is too small to contain the resulting - * string. - */ - goto exit_free; - } - - - /* Open directory stream using wide-character name */ - dirp->wdirp = _wopendir (wname); - if (!dirp->wdirp) { - goto exit_free; - } - - } - - /* Success */ - return dirp; - - /* Failure */ -exit_free: - free (dirp); - return NULL; -} - -/* - * Read next directory entry. - */ -static struct dirent* -readdir( - DIR *dirp) -{ - struct dirent *entry; - - /* - * Read directory entry to buffer. We can safely ignore the return value - * as entry will be set to NULL in case of error. - */ - (void) readdir_r (dirp, &dirp->ent, &entry); - - /* Return pointer to statically allocated directory entry */ - return entry; -} - -/* - * Read next directory entry into called-allocated buffer. - * - * Returns zero on success. If the end of directory stream is reached, then - * sets result to NULL and returns zero. - */ -static int -readdir_r( - DIR *dirp, - struct dirent *entry, - struct dirent **result) -{ - WIN32_FIND_DATAW *datap; - - /* Read next directory entry */ - datap = dirent_next (dirp->wdirp); - if (datap) { - size_t n; - int error; - - /* Attempt to convert file name to multi-byte string */ - error = dirent_wcstombs_s( - &n, entry->d_name, PATH_MAX + 1, datap->cFileName, PATH_MAX + 1); - - /* - * If the file name cannot be represented by a multi-byte string, - * then attempt to use old 8+3 file name. This allows traditional - * Unix-code to access some file names despite of unicode - * characters, although file names may seem unfamiliar to the user. - * - * Be ware that the code below cannot come up with a short file - * name unless the file system provides one. At least - * VirtualBox shared folders fail to do this. - */ - if (error && datap->cAlternateFileName[0] != '\0') { - error = dirent_wcstombs_s( - &n, entry->d_name, PATH_MAX + 1, - datap->cAlternateFileName, PATH_MAX + 1); - } - - if (!error) { - DWORD attr; - - /* Length of file name excluding zero terminator */ - entry->d_namlen = n - 1; - - /* File attributes */ - attr = datap->dwFileAttributes; - if ((attr & FILE_ATTRIBUTE_DEVICE) != 0) { - entry->d_type = DT_CHR; - } else if ((attr & FILE_ATTRIBUTE_DIRECTORY) != 0) { - entry->d_type = DT_DIR; - } else { - entry->d_type = DT_REG; - } - - /* Reset dummy fields */ - entry->d_ino = 0; - entry->d_off = 0; - entry->d_reclen = sizeof (struct dirent); - - } else { - - /* - * Cannot convert file name to multi-byte string so construct - * an erroneous directory entry and return that. Note that - * we cannot return NULL as that would stop the processing - * of directory entries completely. - */ - entry->d_name[0] = '?'; - entry->d_name[1] = '\0'; - entry->d_namlen = 1; - entry->d_type = DT_UNKNOWN; - entry->d_ino = 0; - entry->d_off = -1; - entry->d_reclen = 0; - - } - - /* Return pointer to directory entry */ - *result = entry; - - } else { - - /* No more directory entries */ - *result = NULL; - - } - - return /*OK*/0; -} - -/* - * Close directory stream. - */ -static int -closedir( - DIR *dirp) -{ - int ok; - if (dirp) { - - /* Close wide-character directory stream */ - ok = _wclosedir (dirp->wdirp); - dirp->wdirp = NULL; - - /* Release multi-byte character version */ - free (dirp); - - } else { - - /* Invalid directory stream */ - dirent_set_errno (EBADF); - ok = /*failure*/-1; - - } - return ok; -} - -/* - * Rewind directory stream to beginning. - */ -static void -rewinddir( - DIR* dirp) -{ - /* Rewind wide-character string directory stream */ - _wrewinddir (dirp->wdirp); -} - -/* - * Scan directory for entries. - */ -static int -scandir( - const char *dirname, - struct dirent ***namelist, - int (*filter)(const struct dirent*), - int (*compare)(const struct dirent**, const struct dirent**)) -{ - struct dirent **files = NULL; - size_t size = 0; - size_t allocated = 0; - const size_t init_size = 1; - DIR *dir = NULL; - struct dirent *entry; - struct dirent *tmp = NULL; - size_t i; - int result = 0; - - /* Open directory stream */ - dir = opendir (dirname); - if (dir) { - - /* Read directory entries to memory */ - while (1) { - - /* Enlarge pointer table to make room for another pointer */ - if (size >= allocated) { - void *p; - size_t num_entries; - - /* Compute number of entries in the enlarged pointer table */ - if (size < init_size) { - /* Allocate initial pointer table */ - num_entries = init_size; - } else { - /* Double the size */ - num_entries = size * 2; - } - - /* Allocate first pointer table or enlarge existing table */ - p = realloc (files, sizeof (void*) * num_entries); - if (p != NULL) { - /* Got the memory */ - files = (dirent**) p; - allocated = num_entries; - } else { - /* Out of memory */ - result = -1; - break; - } - - } - - /* Allocate room for temporary directory entry */ - if (tmp == NULL) { - tmp = (struct dirent*) malloc (sizeof (struct dirent)); - if (tmp == NULL) { - /* Cannot allocate temporary directory entry */ - result = -1; - break; - } - } - - /* Read directory entry to temporary area */ - if (readdir_r (dir, tmp, &entry) == /*OK*/0) { - - /* Did we get an entry? */ - if (entry != NULL) { - int pass; - - /* Determine whether to include the entry in result */ - if (filter) { - /* Let the filter function decide */ - pass = filter (tmp); - } else { - /* No filter function, include everything */ - pass = 1; - } - - if (pass) { - /* Store the temporary entry to pointer table */ - files[size++] = tmp; - tmp = NULL; - - /* Keep up with the number of files */ - result++; - } - - } else { - - /* - * End of directory stream reached => sort entries and - * exit. - */ - qsort (files, size, sizeof (void*), - (int (*) (const void*, const void*)) compare); - break; - - } - - } else { - /* Error reading directory entry */ - result = /*Error*/ -1; - break; - } - - } - - } else { - /* Cannot open directory */ - result = /*Error*/ -1; - } - - /* Release temporary directory entry */ - free (tmp); - - /* Release allocated memory on error */ - if (result < 0) { - for (i = 0; i < size; i++) { - free (files[i]); - } - free (files); - files = NULL; - } - - /* Close directory stream */ - if (dir) { - closedir (dir); - } - - /* Pass pointer table to caller */ - if (namelist) { - *namelist = files; - } - return result; -} - -/* Alphabetical sorting */ -static int -alphasort( - const struct dirent **a, const struct dirent **b) -{ - return strcoll ((*a)->d_name, (*b)->d_name); -} - -/* Sort versions */ -static int -versionsort( - const struct dirent **a, const struct dirent **b) -{ - /* FIXME: implement strverscmp and use that */ - return alphasort (a, b); -} - -/* Convert multi-byte string to wide character string */ -static int -dirent_mbstowcs_s( - size_t *pReturnValue, - wchar_t *wcstr, - size_t sizeInWords, - const char *mbstr, - size_t count) -{ - int error; - -#if defined(_MSC_VER) && _MSC_VER >= 1400 - - /* Microsoft Visual Studio 2005 or later */ - error = mbstowcs_s (pReturnValue, wcstr, sizeInWords, mbstr, count); - -#else - - /* Older Visual Studio or non-Microsoft compiler */ - size_t n; - - /* Convert to wide-character string (or count characters) */ - n = mbstowcs (wcstr, mbstr, sizeInWords); - if (!wcstr || n < count) { - - /* Zero-terminate output buffer */ - if (wcstr && sizeInWords) { - if (n >= sizeInWords) { - n = sizeInWords - 1; - } - wcstr[n] = 0; - } - - /* Length of resulting multi-byte string WITH zero terminator */ - if (pReturnValue) { - *pReturnValue = n + 1; - } - - /* Success */ - error = 0; - - } else { - - /* Could not convert string */ - error = 1; - - } - -#endif - return error; -} - -/* Convert wide-character string to multi-byte string */ -static int -dirent_wcstombs_s( - size_t *pReturnValue, - char *mbstr, - size_t sizeInBytes, /* max size of mbstr */ - const wchar_t *wcstr, - size_t count) -{ - int error; - -#if defined(_MSC_VER) && _MSC_VER >= 1400 - - /* Microsoft Visual Studio 2005 or later */ - error = wcstombs_s (pReturnValue, mbstr, sizeInBytes, wcstr, count); - -#else - - /* Older Visual Studio or non-Microsoft compiler */ - size_t n; - - /* Convert to multi-byte string (or count the number of bytes needed) */ - n = wcstombs (mbstr, wcstr, sizeInBytes); - if (!mbstr || n < count) { - - /* Zero-terminate output buffer */ - if (mbstr && sizeInBytes) { - if (n >= sizeInBytes) { - n = sizeInBytes - 1; - } - mbstr[n] = '\0'; - } - - /* Length of resulting multi-bytes string WITH zero-terminator */ - if (pReturnValue) { - *pReturnValue = n + 1; - } - - /* Success */ - error = 0; - - } else { - - /* Cannot convert string */ - error = 1; - - } - -#endif - return error; -} - -/* Set errno variable */ -static void -dirent_set_errno( - int error) -{ -#if defined(_MSC_VER) && _MSC_VER >= 1400 - - /* Microsoft Visual Studio 2005 and later */ - _set_errno (error); - -#else - - /* Non-Microsoft compiler or older Microsoft compiler */ - errno = error; - -#endif -} - - -#ifdef __cplusplus -} -#endif diff --git a/src/mavsdk/plugins/component_information/component_information_impl.cpp b/src/mavsdk/plugins/component_information/component_information_impl.cpp index b85377a638..673ad31501 100644 --- a/src/mavsdk/plugins/component_information/component_information_impl.cpp +++ b/src/mavsdk/plugins/component_information/component_information_impl.cpp @@ -1,13 +1,16 @@ #include "component_information_impl.h" -#include "fs.h" #include "callback_list.tpp" #include +#include #include +#include #include namespace mavsdk { +namespace fs = std::filesystem; + template class CallbackList; ComponentInformationImpl::ComponentInformationImpl(System& system) : PluginImplBase(system) @@ -78,17 +81,19 @@ void ComponentInformationImpl::download_file_async( const auto maybe_tmp_path = create_tmp_directory("mavsdk-component-information-tmp-files"); const auto path_to_download = maybe_tmp_path ? maybe_tmp_path.value() : "./"; - _system_impl->mavlink_ftp().download_async( + _system_impl->mavlink_ftp_client().download_async( path, path_to_download, + false, // Don't use burst for now [path_to_download, callback, path]( - MavlinkFtp::ClientResult download_result, MavlinkFtp::ProgressData progress_data) { - if (download_result == MavlinkFtp::ClientResult::Next) { + MavlinkFtpClient::ClientResult download_result, + MavlinkFtpClient::ProgressData progress_data) { + if (download_result == MavlinkFtpClient::ClientResult::Next) { LogDebug() << "File download progress: " << progress_data.bytes_transferred << '/' << progress_data.total_bytes; } else { LogDebug() << "File download ended with result " << download_result; - if (download_result == MavlinkFtp::ClientResult::Success) { + if (download_result == MavlinkFtpClient::ClientResult::Success) { LogDebug() << "Received file " << path_to_download + "/" + path; callback(path_to_download + "/" + path); } @@ -264,4 +269,30 @@ void ComponentInformationImpl::unsubscribe_float_param( _float_param_update_callbacks.unsubscribe(handle); } +std::optional ComponentInformationImpl::create_tmp_directory(const std::string& prefix) +{ + // Inspired by https://stackoverflow.com/a/58454949/8548472 + const auto tmp_dir = fs::temp_directory_path(); + + std::random_device dev; + std::mt19937 prng(dev()); + std::uniform_int_distribution rand(0); + + static constexpr unsigned max_tries = 100; + + for (unsigned i = 0; i < max_tries; ++i) { + std::stringstream ss; + ss << prefix << '-' << std::hex << rand(prng); + auto path = tmp_dir / ss.str(); + + const auto created = fs::create_directory(path); + if (created) { + return {path.string()}; + } + } + + LogErr() << "Could not create a temporary directory, aborting."; + return {}; +} + } // namespace mavsdk diff --git a/src/mavsdk/plugins/component_information/component_information_impl.h b/src/mavsdk/plugins/component_information/component_information_impl.h index f3cf866f25..153a9aca90 100644 --- a/src/mavsdk/plugins/component_information/component_information_impl.h +++ b/src/mavsdk/plugins/component_information/component_information_impl.h @@ -4,6 +4,9 @@ #include "plugin_impl_base.h" #include "callback_list.h" +#include +#include + namespace mavsdk { class ComponentInformationImpl : public PluginImplBase { @@ -39,6 +42,8 @@ class ComponentInformationImpl : public PluginImplBase { void param_update(const std::string& name, float new_value); + std::optional create_tmp_directory(const std::string& prefix); + std::mutex _mutex{}; std::vector _float_params{}; diff --git a/src/mavsdk/plugins/ftp/ftp.cpp b/src/mavsdk/plugins/ftp/ftp.cpp index 7b61cfba49..eb7ea09be3 100644 --- a/src/mavsdk/plugins/ftp/ftp.cpp +++ b/src/mavsdk/plugins/ftp/ftp.cpp @@ -17,15 +17,13 @@ Ftp::Ftp(std::shared_ptr system) : PluginBase(), _impl{std::make_unique< Ftp::~Ftp() {} -void Ftp::reset_async(const ResultCallback callback) -{ - _impl->reset_async(callback); -} - void Ftp::download_async( - std::string remote_file_path, std::string local_dir, const DownloadCallback& callback) + std::string remote_file_path, + std::string local_dir, + bool use_burst, + const DownloadCallback& callback) { - _impl->download_async(remote_file_path, local_dir, callback); + _impl->download_async(remote_file_path, local_dir, use_burst, callback); } void Ftp::upload_async( @@ -99,21 +97,11 @@ Ftp::are_files_identical(std::string local_file_path, std::string remote_file_pa return _impl->are_files_identical(local_file_path, remote_file_path); } -Ftp::Result Ftp::set_root_directory(std::string root_dir) const -{ - return _impl->set_root_directory(root_dir); -} - Ftp::Result Ftp::set_target_compid(uint32_t compid) const { return _impl->set_target_compid(compid); } -uint32_t Ftp::get_our_compid() const -{ - return _impl->get_our_compid(); -} - bool operator==(const Ftp::ProgressData& lhs, const Ftp::ProgressData& rhs) { return (rhs.bytes_transferred == lhs.bytes_transferred) && (rhs.total_bytes == lhs.total_bytes); diff --git a/src/mavsdk/plugins/ftp/ftp_impl.cpp b/src/mavsdk/plugins/ftp/ftp_impl.cpp index 9ad64193f6..302bbfccd4 100644 --- a/src/mavsdk/plugins/ftp/ftp_impl.cpp +++ b/src/mavsdk/plugins/ftp/ftp_impl.cpp @@ -1,24 +1,7 @@ +#include #include #include -#if defined(WINDOWS) -#include "tronkko_dirent.h" -#include "stackoverflow_unistd.h" -// Fix MSVC error C4003 -// https://stackoverflow.com/a/6884102/8548472 -#ifdef max -#undef max -#endif -#else -#include -#include -#endif -#include -#include -#include - -#include "crc32.h" -#include "fs.h" #include "ftp_impl.h" #include "system.h" @@ -47,20 +30,18 @@ void FtpImpl::enable() {} void FtpImpl::disable() {} -void FtpImpl::reset_async(Ftp::ResultCallback callback) -{ - _system_impl->mavlink_ftp().reset_async([callback, this](MavlinkFtp::ClientResult result) { - callback(result_from_mavlink_ftp_result(result)); - }); -} - void FtpImpl::download_async( - const std::string& remote_path, const std::string& local_folder, Ftp::DownloadCallback callback) + const std::string& remote_path, + const std::string& local_folder, + bool use_burst, + Ftp::DownloadCallback callback) { - _system_impl->mavlink_ftp().download_async( + _system_impl->mavlink_ftp_client().download_async( remote_path, local_folder, - [callback, this](MavlinkFtp::ClientResult result, MavlinkFtp::ProgressData progress_data) { + use_burst, + [callback, this]( + MavlinkFtpClient::ClientResult result, MavlinkFtpClient::ProgressData progress_data) { callback( result_from_mavlink_ftp_result(result), progress_data_from_mavlink_ftp_progress_data(progress_data)); @@ -72,10 +53,11 @@ void FtpImpl::upload_async( const std::string& remote_folder, Ftp::UploadCallback callback) { - _system_impl->mavlink_ftp().upload_async( + _system_impl->mavlink_ftp_client().upload_async( local_file_path, remote_folder, - [callback, this](MavlinkFtp::ClientResult result, MavlinkFtp::ProgressData progress_data) { + [callback, this]( + MavlinkFtpClient::ClientResult result, MavlinkFtpClient::ProgressData progress_data) { callback( result_from_mavlink_ftp_result(result), progress_data_from_mavlink_ftp_progress_data(progress_data)); @@ -84,70 +66,95 @@ void FtpImpl::upload_async( std::pair> FtpImpl::list_directory(const std::string& path) { - auto ret = _system_impl->mavlink_ftp().list_directory(path); - return std::pair{result_from_mavlink_ftp_result(ret.first), ret.second}; + std::promise>> prom; + auto fut = prom.get_future(); + + list_directory_async(path, [&](Ftp::Result result, std::vector list) { + prom.set_value(std::pair>{result, list}); + }); + return fut.get(); } -void FtpImpl::list_directory_async( - const std::string& path, Ftp::ListDirectoryCallback callback, uint32_t offset) +void FtpImpl::list_directory_async(const std::string& path, Ftp::ListDirectoryCallback callback) { - _system_impl->mavlink_ftp().list_directory_async( - path, - [callback, this](MavlinkFtp::ClientResult result, auto&& dirs) { - callback(result_from_mavlink_ftp_result(result), dirs); - }, - offset); + _system_impl->mavlink_ftp_client().list_directory_async( + path, [callback, this](MavlinkFtpClient::ClientResult result, auto&& dirs) { + if (callback) { + _system_impl->call_user_callback([temp_callback = callback, result, dirs, this]() { + temp_callback(result_from_mavlink_ftp_result(result), dirs); + }); + } + }); } Ftp::Result FtpImpl::create_directory(const std::string& path) { - return result_from_mavlink_ftp_result(_system_impl->mavlink_ftp().create_directory(path)); + std::promise prom{}; + auto fut = prom.get_future(); + + create_directory_async(path, [&](Ftp::Result result) { prom.set_value(result); }); + return fut.get(); } void FtpImpl::create_directory_async(const std::string& path, Ftp::ResultCallback callback) { - _system_impl->mavlink_ftp().create_directory_async( - path, [callback, this](MavlinkFtp::ClientResult result) { + _system_impl->mavlink_ftp_client().create_directory_async( + path, [callback, this](MavlinkFtpClient::ClientResult result) { callback(result_from_mavlink_ftp_result(result)); }); } Ftp::Result FtpImpl::remove_directory(const std::string& path) { - return result_from_mavlink_ftp_result(_system_impl->mavlink_ftp().remove_directory(path)); + std::promise prom{}; + auto fut = prom.get_future(); + + remove_directory_async(path, [&](Ftp::Result result) { prom.set_value(result); }); + + return fut.get(); } void FtpImpl::remove_directory_async(const std::string& path, Ftp::ResultCallback callback) { - _system_impl->mavlink_ftp().remove_directory_async( - path, [callback, this](MavlinkFtp::ClientResult result) { + _system_impl->mavlink_ftp_client().remove_directory_async( + path, [callback, this](MavlinkFtpClient::ClientResult result) { callback(result_from_mavlink_ftp_result(result)); }); } Ftp::Result FtpImpl::remove_file(const std::string& path) { - return result_from_mavlink_ftp_result(_system_impl->mavlink_ftp().remove_file(path)); + std::promise prom; + auto fut = prom.get_future(); + + remove_file_async(path, [&](Ftp::Result result) { prom.set_value(result); }); + + return fut.get(); } void FtpImpl::remove_file_async(const std::string& path, Ftp::ResultCallback callback) { - _system_impl->mavlink_ftp().remove_file_async( - path, [callback, this](MavlinkFtp::ClientResult result) { + _system_impl->mavlink_ftp_client().remove_file_async( + path, [callback, this](MavlinkFtpClient::ClientResult result) { callback(result_from_mavlink_ftp_result(result)); }); } Ftp::Result FtpImpl::rename(const std::string& from_path, const std::string& to_path) { - return result_from_mavlink_ftp_result(_system_impl->mavlink_ftp().rename(from_path, to_path)); + std::promise prom{}; + auto fut = prom.get_future(); + + rename_async(from_path, to_path, [&](Ftp::Result result) { prom.set_value(result); }); + + return fut.get(); } void FtpImpl::rename_async( const std::string& from_path, const std::string& to_path, Ftp::ResultCallback callback) { - _system_impl->mavlink_ftp().rename_async( - from_path, to_path, [callback, this](MavlinkFtp::ClientResult result) { + _system_impl->mavlink_ftp_client().rename_async( + from_path, to_path, [callback, this](MavlinkFtpClient::ClientResult result) { callback(result_from_mavlink_ftp_result(result)); }); } @@ -155,8 +162,14 @@ void FtpImpl::rename_async( std::pair FtpImpl::are_files_identical(const std::string& local_path, const std::string& remote_path) { - auto ret = _system_impl->mavlink_ftp().are_files_identical(local_path, remote_path); - return std::pair{result_from_mavlink_ftp_result(ret.first), ret.second}; + std::promise> prom{}; + auto fut = prom.get_future(); + + are_files_identical_async(local_path, remote_path, [&](Ftp::Result result, bool identical) { + prom.set_value(std::pair{result, identical}); + }); + + return fut.get(); } void FtpImpl::are_files_identical_async( @@ -164,56 +177,48 @@ void FtpImpl::are_files_identical_async( const std::string& remote_path, Ftp::AreFilesIdenticalCallback callback) { - _system_impl->mavlink_ftp().are_files_identical_async( - local_path, remote_path, [callback, this](MavlinkFtp::ClientResult result, bool identical) { + _system_impl->mavlink_ftp_client().are_files_identical_async( + local_path, + remote_path, + [callback, this](MavlinkFtpClient::ClientResult result, bool identical) { callback(result_from_mavlink_ftp_result(result), identical); }); } -Ftp::Result FtpImpl::set_root_directory(const std::string& root_dir) -{ - return result_from_mavlink_ftp_result(_system_impl->mavlink_ftp().set_root_directory(root_dir)); -} - -void FtpImpl::set_retries(uint32_t retries) -{ - _system_impl->mavlink_ftp().set_retries(retries); -} - Ftp::Result FtpImpl::set_target_compid(uint8_t component_id) { return result_from_mavlink_ftp_result( - _system_impl->mavlink_ftp().set_target_compid(component_id)); + _system_impl->mavlink_ftp_client().set_target_compid(component_id)); } -Ftp::Result FtpImpl::result_from_mavlink_ftp_result(MavlinkFtp::ClientResult result) +Ftp::Result FtpImpl::result_from_mavlink_ftp_result(MavlinkFtpClient::ClientResult result) { switch (result) { - case MavlinkFtp::ClientResult::Unknown: + case MavlinkFtpClient::ClientResult::Unknown: return Ftp::Result::Unknown; - case MavlinkFtp::ClientResult::Success: + case MavlinkFtpClient::ClientResult::Success: return Ftp::Result::Success; - case MavlinkFtp::ClientResult::Next: + case MavlinkFtpClient::ClientResult::Next: return Ftp::Result::Next; - case MavlinkFtp::ClientResult::Timeout: + case MavlinkFtpClient::ClientResult::Timeout: return Ftp::Result::Timeout; - case MavlinkFtp::ClientResult::Busy: + case MavlinkFtpClient::ClientResult::Busy: return Ftp::Result::Busy; - case MavlinkFtp::ClientResult::FileIoError: + case MavlinkFtpClient::ClientResult::FileIoError: return Ftp::Result::FileIoError; - case MavlinkFtp::ClientResult::FileExists: + case MavlinkFtpClient::ClientResult::FileExists: return Ftp::Result::FileExists; - case MavlinkFtp::ClientResult::FileDoesNotExist: + case MavlinkFtpClient::ClientResult::FileDoesNotExist: return Ftp::Result::FileDoesNotExist; - case MavlinkFtp::ClientResult::FileProtected: + case MavlinkFtpClient::ClientResult::FileProtected: return Ftp::Result::FileProtected; - case MavlinkFtp::ClientResult::InvalidParameter: + case MavlinkFtpClient::ClientResult::InvalidParameter: return Ftp::Result::InvalidParameter; - case MavlinkFtp::ClientResult::Unsupported: + case MavlinkFtpClient::ClientResult::Unsupported: return Ftp::Result::Unsupported; - case MavlinkFtp::ClientResult::ProtocolError: + case MavlinkFtpClient::ClientResult::ProtocolError: return Ftp::Result::ProtocolError; - case MavlinkFtp::ClientResult::NoSystem: + case MavlinkFtpClient::ClientResult::NoSystem: return Ftp::Result::NoSystem; default: return Ftp::Result::Unknown; @@ -221,7 +226,7 @@ Ftp::Result FtpImpl::result_from_mavlink_ftp_result(MavlinkFtp::ClientResult res } Ftp::ProgressData -FtpImpl::progress_data_from_mavlink_ftp_progress_data(MavlinkFtp::ProgressData progress_data) +FtpImpl::progress_data_from_mavlink_ftp_progress_data(MavlinkFtpClient::ProgressData progress_data) { return {progress_data.bytes_transferred, progress_data.total_bytes}; } diff --git a/src/mavsdk/plugins/ftp/ftp_impl.h b/src/mavsdk/plugins/ftp/ftp_impl.h index 8503bde5a6..b2d685ed1a 100644 --- a/src/mavsdk/plugins/ftp/ftp_impl.h +++ b/src/mavsdk/plugins/ftp/ftp_impl.h @@ -8,14 +8,6 @@ #include "plugins/ftp/ftp.h" #include "plugin_impl_base.h" -// As found in -// https://stackoverflow.com/questions/1537964#answer-3312896 -#ifdef _MSC_VER // MSVC -#define PACK(__Declaration__) __pragma(pack(push, 1)) __Declaration__ __pragma(pack(pop)) -#else -#define PACK(__Declaration__) __Declaration__ __attribute__((__packed__)) -#endif - namespace mavsdk { class FtpImpl : public PluginImplBase { @@ -45,13 +37,13 @@ class FtpImpl : public PluginImplBase { void download_async( const std::string& remote_file_path, const std::string& local_folder, + bool use_burst, Ftp::DownloadCallback callback); void upload_async( const std::string& local_file_path, const std::string& remote_folder, Ftp::UploadCallback callback); - void list_directory_async( - const std::string& path, Ftp::ListDirectoryCallback callback, uint32_t offset = 0); + void list_directory_async(const std::string& path, Ftp::ListDirectoryCallback callback); void create_directory_async(const std::string& path, Ftp::ResultCallback callback); void remove_directory_async(const std::string& path, Ftp::ResultCallback callback); void remove_file_async(const std::string& path, Ftp::ResultCallback callback); @@ -62,15 +54,12 @@ class FtpImpl : public PluginImplBase { const std::string& remote_path, Ftp::AreFilesIdenticalCallback callback); - void set_retries(uint32_t retries); - Ftp::Result set_root_directory(const std::string& root_dir); - uint8_t get_our_compid() { return _system_impl->get_own_component_id(); }; Ftp::Result set_target_compid(uint8_t component_id); private: - Ftp::Result result_from_mavlink_ftp_result(MavlinkFtp::ClientResult result); + Ftp::Result result_from_mavlink_ftp_result(MavlinkFtpClient::ClientResult result); Ftp::ProgressData - progress_data_from_mavlink_ftp_progress_data(MavlinkFtp::ProgressData progress_data); + progress_data_from_mavlink_ftp_progress_data(MavlinkFtpClient::ProgressData progress_data); }; } // namespace mavsdk diff --git a/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h b/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h index 4dcff04d4e..c352a12a68 100644 --- a/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h +++ b/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h @@ -111,13 +111,6 @@ class Ftp : public PluginBase { */ using ResultCallback = std::function; - /** - * @brief Resets FTP server in case there are stale open sessions. - * - * This function is non-blocking. - */ - void reset_async(const ResultCallback callback); - /** * @brief Callback type for download_async. */ @@ -127,7 +120,10 @@ class Ftp : public PluginBase { * @brief Downloads a file to local directory. */ void download_async( - std::string remote_file_path, std::string local_dir, const DownloadCallback& callback); + std::string remote_file_path, + std::string local_dir, + bool use_burst, + const DownloadCallback& callback); /** * @brief Callback type for upload_async. @@ -251,15 +247,6 @@ class Ftp : public PluginBase { std::pair are_files_identical(std::string local_file_path, std::string remote_file_path) const; - /** - * @brief Set root directory for MAVLink FTP server. - * - * This function is blocking. - * - * @return Result of request. - */ - Result set_root_directory(std::string root_dir) const; - /** * @brief Set target component ID. By default it is the autopilot. * @@ -269,15 +256,6 @@ class Ftp : public PluginBase { */ Result set_target_compid(uint32_t compid) const; - /** - * @brief Get our own component ID. - * - * This function is blocking. - * - * @return Result of request. - */ - uint32_t get_our_compid() const; - /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/ftp_server/CMakeLists.txt b/src/mavsdk/plugins/ftp_server/CMakeLists.txt new file mode 100644 index 0000000000..a7272ab6d7 --- /dev/null +++ b/src/mavsdk/plugins/ftp_server/CMakeLists.txt @@ -0,0 +1,15 @@ +target_sources(mavsdk + PRIVATE + ftp_server.cpp + ftp_server_impl.cpp +) + +target_include_directories(mavsdk PUBLIC + $ + $ + ) + +install(FILES + include/plugins/ftp_server/ftp_server.h + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/ftp_server +) \ No newline at end of file diff --git a/src/mavsdk/plugins/ftp_server/ftp_server.cpp b/src/mavsdk/plugins/ftp_server/ftp_server.cpp new file mode 100644 index 0000000000..78613d2b60 --- /dev/null +++ b/src/mavsdk/plugins/ftp_server/ftp_server.cpp @@ -0,0 +1,40 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/ftp_server/ftp_server.proto) + +#include + +#include "ftp_server_impl.h" +#include "plugins/ftp_server/ftp_server.h" + +namespace mavsdk { + +FtpServer::FtpServer(std::shared_ptr server_component) : + ServerPluginBase(), + _impl{std::make_unique(server_component)} +{} + +FtpServer::~FtpServer() {} + +FtpServer::Result FtpServer::set_root_dir(std::string path) const +{ + return _impl->set_root_dir(path); +} + +std::ostream& operator<<(std::ostream& str, FtpServer::Result const& result) +{ + switch (result) { + case FtpServer::Result::Unknown: + return str << "Unknown"; + case FtpServer::Result::Success: + return str << "Success"; + case FtpServer::Result::DoesNotExist: + return str << "Does Not Exist"; + case FtpServer::Result::Busy: + return str << "Busy"; + default: + return str << "Unknown"; + } +} + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/ftp_server/ftp_server_impl.cpp b/src/mavsdk/plugins/ftp_server/ftp_server_impl.cpp new file mode 100644 index 0000000000..e36a996308 --- /dev/null +++ b/src/mavsdk/plugins/ftp_server/ftp_server_impl.cpp @@ -0,0 +1,30 @@ +#include "ftp_server_impl.h" + +namespace mavsdk { + +FtpServerImpl::FtpServerImpl(std::shared_ptr server_component) : + ServerPluginImplBase(server_component) +{ + _server_component_impl->register_plugin(this); +} + +FtpServerImpl::~FtpServerImpl() +{ + _server_component_impl->unregister_plugin(this); +} + +void FtpServerImpl::init() {} + +void FtpServerImpl::deinit() {} + +FtpServer::Result FtpServerImpl::set_root_dir(const std::string& path) +{ + // TODO: only do this when the server is not busy. + // TODO: check if it exists + + _server_component_impl->mavlink_ftp_server().set_root_directory(path); + + return FtpServer::Result::Success; +} + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/ftp_server/ftp_server_impl.h b/src/mavsdk/plugins/ftp_server/ftp_server_impl.h new file mode 100644 index 0000000000..18102e391e --- /dev/null +++ b/src/mavsdk/plugins/ftp_server/ftp_server_impl.h @@ -0,0 +1,27 @@ +#pragma once + +#include "plugins/ftp_server/ftp_server.h" + +#include +#include +#include "server_plugin_impl_base.h" + +namespace mavsdk { + +class FtpServerImpl : public ServerPluginImplBase { +public: + explicit FtpServerImpl(std::shared_ptr server_component); + + ~FtpServerImpl() override; + + void init() override; + void deinit() override; + + FtpServer::Result set_root_dir(const std::string& path); + +private: + std::mutex _root_dir_mutex{}; + std::string _root_dir{}; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/ftp_server/include/plugins/ftp_server/ftp_server.h b/src/mavsdk/plugins/ftp_server/include/plugins/ftp_server/ftp_server.h new file mode 100644 index 0000000000..0a4e79cd9d --- /dev/null +++ b/src/mavsdk/plugins/ftp_server/include/plugins/ftp_server/ftp_server.h @@ -0,0 +1,99 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see https://github.com/mavlink/MAVSDK-Proto/blob/main/protos/ftp_server/ftp_server.proto) + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "server_plugin_base.h" + +#include "handle.h" + +namespace mavsdk { + +class ServerComponent; +class FtpServerImpl; + +/** + * @brief Provide files or directories to transfer. + */ +class FtpServer : public ServerPluginBase { +public: + /** + * @brief Constructor. Creates the plugin for a ServerComponent instance. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto ftp_server = FtpServer(server_component); + * ``` + * + * @param server_component The ServerComponent instance associated with this server plugin. + */ + explicit FtpServer(std::shared_ptr server_component); + + /** + * @brief Destructor (internal use only). + */ + ~FtpServer() override; + + /** + * @brief Possible results returned for FTP server requests. + */ + enum class Result { + Unknown, /**< @brief Unknown result. */ + Success, /**< @brief Request succeeded. */ + DoesNotExist, /**< @brief Directory does not exist. */ + Busy, /**< @brief Operations in progress. */ + }; + + /** + * @brief Stream operator to print information about a `FtpServer::Result`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, FtpServer::Result const& result); + + /** + * @brief Callback type for asynchronous FtpServer calls. + */ + using ResultCallback = std::function; + + /** + * @brief Set root directory. + * + * This is the directory that can then be accessed by a client. + * The directory needs to exist when this is called. + * The permissions are the same as the file permission for the user running the server. + * The root directory can't be changed while an FTP process is in progress. + * + * This function is blocking. + * + * @return Result of request. + */ + Result set_root_dir(std::string path) const; + + /** + * @brief Copy constructor. + */ + FtpServer(const FtpServer& other); + + /** + * @brief Equality operator (object is not copyable). + */ + const FtpServer& operator=(const FtpServer&) = delete; + +private: + /** @private Underlying implementation, set at instantiation */ + std::unique_ptr _impl; +}; + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/log_files/log_files_impl.cpp b/src/mavsdk/plugins/log_files/log_files_impl.cpp index cee49b40f2..0eaaa0bc37 100644 --- a/src/mavsdk/plugins/log_files/log_files_impl.cpp +++ b/src/mavsdk/plugins/log_files/log_files_impl.cpp @@ -1,16 +1,18 @@ #include "log_files_impl.h" #include "mavlink_address.h" #include "mavsdk_impl.h" -#include "filesystem_include.h" #include "unused.h" #include #include #include #include +#include namespace mavsdk { +namespace fs = std::filesystem; + LogFilesImpl::LogFilesImpl(System& system) : PluginImplBase(system) { _system_impl->register_plugin(this); diff --git a/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.cc b/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.cc index 59ea7005e6..90b408b7a6 100644 --- a/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.cc @@ -24,7 +24,6 @@ namespace rpc { namespace ftp { static const char* FtpService_method_names[] = { - "/mavsdk.rpc.ftp.FtpService/Reset", "/mavsdk.rpc.ftp.FtpService/SubscribeDownload", "/mavsdk.rpc.ftp.FtpService/SubscribeUpload", "/mavsdk.rpc.ftp.FtpService/ListDirectory", @@ -33,9 +32,7 @@ static const char* FtpService_method_names[] = { "/mavsdk.rpc.ftp.FtpService/RemoveFile", "/mavsdk.rpc.ftp.FtpService/Rename", "/mavsdk.rpc.ftp.FtpService/AreFilesIdentical", - "/mavsdk.rpc.ftp.FtpService/SetRootDirectory", "/mavsdk.rpc.ftp.FtpService/SetTargetCompid", - "/mavsdk.rpc.ftp.FtpService/GetOurCompid", }; std::unique_ptr< FtpService::Stub> FtpService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -45,43 +42,17 @@ std::unique_ptr< FtpService::Stub> FtpService::NewStub(const std::shared_ptr< :: } FtpService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) - : channel_(channel), rpcmethod_Reset_(FtpService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeDownload_(FtpService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeUpload_(FtpService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_ListDirectory_(FtpService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_CreateDirectory_(FtpService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_RemoveDirectory_(FtpService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_RemoveFile_(FtpService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_Rename_(FtpService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_AreFilesIdentical_(FtpService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRootDirectory_(FtpService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetTargetCompid_(FtpService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_GetOurCompid_(FtpService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + : channel_(channel), rpcmethod_SubscribeDownload_(FtpService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeUpload_(FtpService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_ListDirectory_(FtpService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_CreateDirectory_(FtpService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RemoveDirectory_(FtpService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RemoveFile_(FtpService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_Rename_(FtpService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_AreFilesIdentical_(FtpService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetTargetCompid_(FtpService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} -::grpc::Status FtpService::Stub::Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::mavsdk::rpc::ftp::ResetResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_Reset_, context, request, response); -} - -void FtpService::Stub::async::Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_Reset_, context, request, response, std::move(f)); -} - -void FtpService::Stub::async::Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_Reset_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>* FtpService::Stub::PrepareAsyncResetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::ftp::ResetResponse, ::mavsdk::rpc::ftp::ResetRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_Reset_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>* FtpService::Stub::AsyncResetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncResetRaw(context, request, cq); - result->StartCall(); - return result; -} - ::grpc::ClientReader< ::mavsdk::rpc::ftp::DownloadResponse>* FtpService::Stub::SubscribeDownloadRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::ftp::DownloadResponse>::Create(channel_.get(), rpcmethod_SubscribeDownload_, context, request); } @@ -252,29 +223,6 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse return result; } -::grpc::Status FtpService::Stub::SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetRootDirectory_, context, request, response); -} - -void FtpService::Stub::async::SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRootDirectory_, context, request, response, std::move(f)); -} - -void FtpService::Stub::async::SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRootDirectory_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* FtpService::Stub::PrepareAsyncSetRootDirectoryRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::ftp::SetRootDirectoryResponse, ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetRootDirectory_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* FtpService::Stub::AsyncSetRootDirectoryRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncSetRootDirectoryRaw(context, request, cq); - result->StartCall(); - return result; -} - ::grpc::Status FtpService::Stub::SetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::ftp::SetTargetCompidRequest, ::mavsdk::rpc::ftp::SetTargetCompidResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetTargetCompid_, context, request, response); } @@ -298,42 +246,9 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetTargetCompidResponse>* return result; } -::grpc::Status FtpService::Stub::GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetOurCompid_, context, request, response); -} - -void FtpService::Stub::async::GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetOurCompid_, context, request, response, std::move(f)); -} - -void FtpService::Stub::async::GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetOurCompid_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>* FtpService::Stub::PrepareAsyncGetOurCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::ftp::GetOurCompidResponse, ::mavsdk::rpc::ftp::GetOurCompidRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetOurCompid_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>* FtpService::Stub::AsyncGetOurCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncGetOurCompidRaw(context, request, cq); - result->StartCall(); - return result; -} - FtpService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( FtpService_method_names[0], - ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](FtpService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::ftp::ResetRequest* req, - ::mavsdk::rpc::ftp::ResetResponse* resp) { - return service->Reset(ctx, req, resp); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[1], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< FtpService::Service, ::mavsdk::rpc::ftp::SubscribeDownloadRequest, ::mavsdk::rpc::ftp::DownloadResponse>( [](FtpService::Service* service, @@ -343,7 +258,7 @@ FtpService::Service::Service() { return service->SubscribeDownload(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[2], + FtpService_method_names[1], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< FtpService::Service, ::mavsdk::rpc::ftp::SubscribeUploadRequest, ::mavsdk::rpc::ftp::UploadResponse>( [](FtpService::Service* service, @@ -353,7 +268,7 @@ FtpService::Service::Service() { return service->SubscribeUpload(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[3], + FtpService_method_names[2], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::ListDirectoryRequest, ::mavsdk::rpc::ftp::ListDirectoryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](FtpService::Service* service, @@ -363,7 +278,7 @@ FtpService::Service::Service() { return service->ListDirectory(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[4], + FtpService_method_names[3], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::CreateDirectoryRequest, ::mavsdk::rpc::ftp::CreateDirectoryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](FtpService::Service* service, @@ -373,7 +288,7 @@ FtpService::Service::Service() { return service->CreateDirectory(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[5], + FtpService_method_names[4], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::RemoveDirectoryRequest, ::mavsdk::rpc::ftp::RemoveDirectoryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](FtpService::Service* service, @@ -383,7 +298,7 @@ FtpService::Service::Service() { return service->RemoveDirectory(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[6], + FtpService_method_names[5], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::RemoveFileRequest, ::mavsdk::rpc::ftp::RemoveFileResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](FtpService::Service* service, @@ -393,7 +308,7 @@ FtpService::Service::Service() { return service->RemoveFile(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[7], + FtpService_method_names[6], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::RenameRequest, ::mavsdk::rpc::ftp::RenameResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](FtpService::Service* service, @@ -403,7 +318,7 @@ FtpService::Service::Service() { return service->Rename(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[8], + FtpService_method_names[7], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::AreFilesIdenticalRequest, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](FtpService::Service* service, @@ -413,17 +328,7 @@ FtpService::Service::Service() { return service->AreFilesIdentical(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[9], - ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](FtpService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* req, - ::mavsdk::rpc::ftp::SetRootDirectoryResponse* resp) { - return service->SetRootDirectory(ctx, req, resp); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[10], + FtpService_method_names[8], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::SetTargetCompidRequest, ::mavsdk::rpc::ftp::SetTargetCompidResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](FtpService::Service* service, @@ -432,28 +337,11 @@ FtpService::Service::Service() { ::mavsdk::rpc::ftp::SetTargetCompidResponse* resp) { return service->SetTargetCompid(ctx, req, resp); }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - FtpService_method_names[11], - ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< FtpService::Service, ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](FtpService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::ftp::GetOurCompidRequest* req, - ::mavsdk::rpc::ftp::GetOurCompidResponse* resp) { - return service->GetOurCompid(ctx, req, resp); - }, this))); } FtpService::Service::~Service() { } -::grpc::Status FtpService::Service::Reset(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response) { - (void) context; - (void) request; - (void) response; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - ::grpc::Status FtpService::Service::SubscribeDownload(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::ftp::DownloadResponse>* writer) { (void) context; (void) request; @@ -510,13 +398,6 @@ ::grpc::Status FtpService::Service::AreFilesIdentical(::grpc::ServerContext* con return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status FtpService::Service::SetRootDirectory(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response) { - (void) context; - (void) request; - (void) response; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - ::grpc::Status FtpService::Service::SetTargetCompid(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response) { (void) context; (void) request; @@ -524,13 +405,6 @@ ::grpc::Status FtpService::Service::SetTargetCompid(::grpc::ServerContext* conte return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status FtpService::Service::GetOurCompid(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response) { - (void) context; - (void) request; - (void) response; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.h b/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.h index 08afe59073..b7ca4778f6 100644 --- a/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.h +++ b/src/mavsdk_server/src/generated/ftp/ftp.grpc.pb.h @@ -40,15 +40,6 @@ class FtpService final { public: virtual ~StubInterface() {} // - // Resets FTP server in case there are stale open sessions. - virtual ::grpc::Status Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::mavsdk::rpc::ftp::ResetResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::ResetResponse>> AsyncReset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::ResetResponse>>(AsyncResetRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::ResetResponse>> PrepareAsyncReset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::ResetResponse>>(PrepareAsyncResetRaw(context, request, cq)); - } - // // Downloads a file to local directory. std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::ftp::DownloadResponse>> SubscribeDownload(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::ftp::DownloadResponse>>(SubscribeDownloadRaw(context, request)); @@ -125,15 +116,6 @@ class FtpService final { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>>(PrepareAsyncAreFilesIdenticalRaw(context, request, cq)); } // - // Set root directory for MAVLink FTP server. - virtual ::grpc::Status SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>> AsyncSetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>>(AsyncSetRootDirectoryRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>> PrepareAsyncSetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>>(PrepareAsyncSetRootDirectoryRaw(context, request, cq)); - } - // // Set target component ID. By default it is the autopilot. virtual ::grpc::Status SetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetTargetCompidResponse>> AsyncSetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) { @@ -142,23 +124,10 @@ class FtpService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetTargetCompidResponse>> PrepareAsyncSetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetTargetCompidResponse>>(PrepareAsyncSetTargetCompidRaw(context, request, cq)); } - // - // Get our own component ID. - virtual ::grpc::Status GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::GetOurCompidResponse>> AsyncGetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::GetOurCompidResponse>>(AsyncGetOurCompidRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::GetOurCompidResponse>> PrepareAsyncGetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::GetOurCompidResponse>>(PrepareAsyncGetOurCompidRaw(context, request, cq)); - } class async_interface { public: virtual ~async_interface() {} // - // Resets FTP server in case there are stale open sessions. - virtual void Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response, std::function) = 0; - virtual void Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // // Downloads a file to local directory. virtual void SubscribeDownload(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::ftp::DownloadResponse>* reactor) = 0; // @@ -189,24 +158,14 @@ class FtpService final { virtual void AreFilesIdentical(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* request, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* response, std::function) = 0; virtual void AreFilesIdentical(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* request, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // - // Set root directory for MAVLink FTP server. - virtual void SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response, std::function) = 0; - virtual void SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // // Set target component ID. By default it is the autopilot. virtual void SetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response, std::function) = 0; virtual void SetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // - // Get our own component ID. - virtual void GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response, std::function) = 0; - virtual void GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } class async_interface* experimental_async() { return async(); } private: - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::ResetResponse>* AsyncResetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::ResetResponse>* PrepareAsyncResetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::ftp::DownloadResponse>* SubscribeDownloadRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::ftp::DownloadResponse>* AsyncSubscribeDownloadRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::ftp::DownloadResponse>* PrepareAsyncSubscribeDownloadRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -225,23 +184,12 @@ class FtpService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::RenameResponse>* PrepareAsyncRenameRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::RenameRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>* AsyncAreFilesIdenticalRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>* PrepareAsyncAreFilesIdenticalRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* AsyncSetRootDirectoryRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* PrepareAsyncSetRootDirectoryRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetTargetCompidResponse>* AsyncSetTargetCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::SetTargetCompidResponse>* PrepareAsyncSetTargetCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::GetOurCompidResponse>* AsyncGetOurCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp::GetOurCompidResponse>* PrepareAsyncGetOurCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); - ::grpc::Status Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::mavsdk::rpc::ftp::ResetResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>> AsyncReset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>>(AsyncResetRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>> PrepareAsyncReset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>>(PrepareAsyncResetRaw(context, request, cq)); - } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::ftp::DownloadResponse>> SubscribeDownload(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::ftp::DownloadResponse>>(SubscribeDownloadRaw(context, request)); } @@ -302,13 +250,6 @@ class FtpService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>> PrepareAsyncAreFilesIdentical(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>>(PrepareAsyncAreFilesIdenticalRaw(context, request, cq)); } - ::grpc::Status SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>> AsyncSetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>>(AsyncSetRootDirectoryRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>> PrepareAsyncSetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>>(PrepareAsyncSetRootDirectoryRaw(context, request, cq)); - } ::grpc::Status SetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetTargetCompidResponse>> AsyncSetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetTargetCompidResponse>>(AsyncSetTargetCompidRaw(context, request, cq)); @@ -316,18 +257,9 @@ class FtpService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetTargetCompidResponse>> PrepareAsyncSetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetTargetCompidResponse>>(PrepareAsyncSetTargetCompidRaw(context, request, cq)); } - ::grpc::Status GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>> AsyncGetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>>(AsyncGetOurCompidRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>> PrepareAsyncGetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>>(PrepareAsyncGetOurCompidRaw(context, request, cq)); - } class async final : public StubInterface::async_interface { public: - void Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response, std::function) override; - void Reset(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeDownload(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::ftp::DownloadResponse>* reactor) override; void SubscribeUpload(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeUploadRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::ftp::UploadResponse>* reactor) override; void ListDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ListDirectoryRequest* request, ::mavsdk::rpc::ftp::ListDirectoryResponse* response, std::function) override; @@ -342,12 +274,8 @@ class FtpService final { void Rename(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::RenameRequest* request, ::mavsdk::rpc::ftp::RenameResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void AreFilesIdentical(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* request, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* response, std::function) override; void AreFilesIdentical(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* request, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response, std::function) override; - void SetRootDirectory(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response, std::function) override; void SetTargetCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response, std::function) override; - void GetOurCompid(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -359,8 +287,6 @@ class FtpService final { private: std::shared_ptr< ::grpc::ChannelInterface> channel_; class async async_stub_{this}; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>* AsyncResetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::ResetResponse>* PrepareAsyncResetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::ResetRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::ftp::DownloadResponse>* SubscribeDownloadRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::ftp::DownloadResponse>* AsyncSubscribeDownloadRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::ftp::DownloadResponse>* PrepareAsyncSubscribeDownloadRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest& request, ::grpc::CompletionQueue* cq) override; @@ -379,13 +305,8 @@ class FtpService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::RenameResponse>* PrepareAsyncRenameRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::RenameRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>* AsyncAreFilesIdenticalRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>* PrepareAsyncAreFilesIdenticalRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* AsyncSetRootDirectoryRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* PrepareAsyncSetRootDirectoryRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetTargetCompidResponse>* AsyncSetTargetCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::SetTargetCompidResponse>* PrepareAsyncSetTargetCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>* AsyncGetOurCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp::GetOurCompidResponse>* PrepareAsyncGetOurCompidRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest& request, ::grpc::CompletionQueue* cq) override; - const ::grpc::internal::RpcMethod rpcmethod_Reset_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeDownload_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeUpload_; const ::grpc::internal::RpcMethod rpcmethod_ListDirectory_; @@ -394,9 +315,7 @@ class FtpService final { const ::grpc::internal::RpcMethod rpcmethod_RemoveFile_; const ::grpc::internal::RpcMethod rpcmethod_Rename_; const ::grpc::internal::RpcMethod rpcmethod_AreFilesIdentical_; - const ::grpc::internal::RpcMethod rpcmethod_SetRootDirectory_; const ::grpc::internal::RpcMethod rpcmethod_SetTargetCompid_; - const ::grpc::internal::RpcMethod rpcmethod_GetOurCompid_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -405,9 +324,6 @@ class FtpService final { Service(); virtual ~Service(); // - // Resets FTP server in case there are stale open sessions. - virtual ::grpc::Status Reset(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response); - // // Downloads a file to local directory. virtual ::grpc::Status SubscribeDownload(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::ftp::DownloadResponse>* writer); // @@ -432,34 +348,8 @@ class FtpService final { // Compares a local file to a remote file using a CRC32 checksum. virtual ::grpc::Status AreFilesIdentical(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* request, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* response); // - // Set root directory for MAVLink FTP server. - virtual ::grpc::Status SetRootDirectory(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response); - // // Set target component ID. By default it is the autopilot. virtual ::grpc::Status SetTargetCompid(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response); - // - // Get our own component ID. - virtual ::grpc::Status GetOurCompid(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response); - }; - template - class WithAsyncMethod_Reset : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_Reset() { - ::grpc::Service::MarkMethodAsync(0); - } - ~WithAsyncMethod_Reset() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Reset(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::ResetRequest* /*request*/, ::mavsdk::rpc::ftp::ResetResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestReset(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::ResetRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::ResetResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } }; template class WithAsyncMethod_SubscribeDownload : public BaseClass { @@ -467,7 +357,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeDownload() { - ::grpc::Service::MarkMethodAsync(1); + ::grpc::Service::MarkMethodAsync(0); } ~WithAsyncMethod_SubscribeDownload() override { BaseClassMustBeDerivedFromService(this); @@ -478,7 +368,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeDownload(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::SubscribeDownloadRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::ftp::DownloadResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(1, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(0, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -487,7 +377,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeUpload() { - ::grpc::Service::MarkMethodAsync(2); + ::grpc::Service::MarkMethodAsync(1); } ~WithAsyncMethod_SubscribeUpload() override { BaseClassMustBeDerivedFromService(this); @@ -498,7 +388,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeUpload(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::SubscribeUploadRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::ftp::UploadResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(2, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(1, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -507,7 +397,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ListDirectory() { - ::grpc::Service::MarkMethodAsync(3); + ::grpc::Service::MarkMethodAsync(2); } ~WithAsyncMethod_ListDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -518,7 +408,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestListDirectory(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::ListDirectoryRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::ListDirectoryResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -527,7 +417,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_CreateDirectory() { - ::grpc::Service::MarkMethodAsync(4); + ::grpc::Service::MarkMethodAsync(3); } ~WithAsyncMethod_CreateDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -538,7 +428,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestCreateDirectory(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::CreateDirectoryRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::CreateDirectoryResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -547,7 +437,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RemoveDirectory() { - ::grpc::Service::MarkMethodAsync(5); + ::grpc::Service::MarkMethodAsync(4); } ~WithAsyncMethod_RemoveDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -558,7 +448,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRemoveDirectory(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::RemoveDirectoryRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::RemoveDirectoryResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -567,7 +457,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RemoveFile() { - ::grpc::Service::MarkMethodAsync(6); + ::grpc::Service::MarkMethodAsync(5); } ~WithAsyncMethod_RemoveFile() override { BaseClassMustBeDerivedFromService(this); @@ -578,7 +468,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRemoveFile(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::RemoveFileRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::RemoveFileResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -587,7 +477,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_Rename() { - ::grpc::Service::MarkMethodAsync(7); + ::grpc::Service::MarkMethodAsync(6); } ~WithAsyncMethod_Rename() override { BaseClassMustBeDerivedFromService(this); @@ -598,7 +488,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRename(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::RenameRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::RenameResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -607,7 +497,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_AreFilesIdentical() { - ::grpc::Service::MarkMethodAsync(8); + ::grpc::Service::MarkMethodAsync(7); } ~WithAsyncMethod_AreFilesIdentical() override { BaseClassMustBeDerivedFromService(this); @@ -618,27 +508,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestAreFilesIdentical(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_SetRootDirectory : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SetRootDirectory() { - ::grpc::Service::MarkMethodAsync(9); - } - ~WithAsyncMethod_SetRootDirectory() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRootDirectory(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* /*request*/, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSetRootDirectory(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -647,7 +517,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetTargetCompid() { - ::grpc::Service::MarkMethodAsync(10); + ::grpc::Service::MarkMethodAsync(8); } ~WithAsyncMethod_SetTargetCompid() override { BaseClassMustBeDerivedFromService(this); @@ -658,64 +528,17 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetTargetCompid(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::SetTargetCompidResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(10, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_GetOurCompid : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_GetOurCompid() { - ::grpc::Service::MarkMethodAsync(11); - } - ~WithAsyncMethod_GetOurCompid() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status GetOurCompid(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::GetOurCompidRequest* /*request*/, ::mavsdk::rpc::ftp::GetOurCompidResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestGetOurCompid(::grpc::ServerContext* context, ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp::GetOurCompidResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(11, context, request, response, new_call_cq, notification_cq, tag); - } - }; - typedef WithAsyncMethod_Reset > > > > > > > > > > > AsyncService; - template - class WithCallbackMethod_Reset : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_Reset() { - ::grpc::Service::MarkMethodCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::ResetRequest* request, ::mavsdk::rpc::ftp::ResetResponse* response) { return this->Reset(context, request, response); }));} - void SetMessageAllocatorFor_Reset( - ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_Reset() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Reset(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::ResetRequest* /*request*/, ::mavsdk::rpc::ftp::ResetResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); } - virtual ::grpc::ServerUnaryReactor* Reset( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::ftp::ResetRequest* /*request*/, ::mavsdk::rpc::ftp::ResetResponse* /*response*/) { return nullptr; } }; + typedef WithAsyncMethod_SubscribeDownload > > > > > > > > AsyncService; template class WithCallbackMethod_SubscribeDownload : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeDownload() { - ::grpc::Service::MarkMethodCallback(1, + ::grpc::Service::MarkMethodCallback(0, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::ftp::SubscribeDownloadRequest, ::mavsdk::rpc::ftp::DownloadResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::SubscribeDownloadRequest* request) { return this->SubscribeDownload(context, request); })); @@ -737,7 +560,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeUpload() { - ::grpc::Service::MarkMethodCallback(2, + ::grpc::Service::MarkMethodCallback(1, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::ftp::SubscribeUploadRequest, ::mavsdk::rpc::ftp::UploadResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::SubscribeUploadRequest* request) { return this->SubscribeUpload(context, request); })); @@ -759,13 +582,13 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ListDirectory() { - ::grpc::Service::MarkMethodCallback(3, + ::grpc::Service::MarkMethodCallback(2, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::ListDirectoryRequest, ::mavsdk::rpc::ftp::ListDirectoryResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::ListDirectoryRequest* request, ::mavsdk::rpc::ftp::ListDirectoryResponse* response) { return this->ListDirectory(context, request, response); }));} void SetMessageAllocatorFor_ListDirectory( ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::ListDirectoryRequest, ::mavsdk::rpc::ftp::ListDirectoryResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::ListDirectoryRequest, ::mavsdk::rpc::ftp::ListDirectoryResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -786,13 +609,13 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_CreateDirectory() { - ::grpc::Service::MarkMethodCallback(4, + ::grpc::Service::MarkMethodCallback(3, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::CreateDirectoryRequest, ::mavsdk::rpc::ftp::CreateDirectoryResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::CreateDirectoryRequest* request, ::mavsdk::rpc::ftp::CreateDirectoryResponse* response) { return this->CreateDirectory(context, request, response); }));} void SetMessageAllocatorFor_CreateDirectory( ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::CreateDirectoryRequest, ::mavsdk::rpc::ftp::CreateDirectoryResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(4); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::CreateDirectoryRequest, ::mavsdk::rpc::ftp::CreateDirectoryResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -813,13 +636,13 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RemoveDirectory() { - ::grpc::Service::MarkMethodCallback(5, + ::grpc::Service::MarkMethodCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::RemoveDirectoryRequest, ::mavsdk::rpc::ftp::RemoveDirectoryResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::RemoveDirectoryRequest* request, ::mavsdk::rpc::ftp::RemoveDirectoryResponse* response) { return this->RemoveDirectory(context, request, response); }));} void SetMessageAllocatorFor_RemoveDirectory( ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::RemoveDirectoryRequest, ::mavsdk::rpc::ftp::RemoveDirectoryResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(4); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::RemoveDirectoryRequest, ::mavsdk::rpc::ftp::RemoveDirectoryResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -840,13 +663,13 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RemoveFile() { - ::grpc::Service::MarkMethodCallback(6, + ::grpc::Service::MarkMethodCallback(5, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::RemoveFileRequest, ::mavsdk::rpc::ftp::RemoveFileResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::RemoveFileRequest* request, ::mavsdk::rpc::ftp::RemoveFileResponse* response) { return this->RemoveFile(context, request, response); }));} void SetMessageAllocatorFor_RemoveFile( ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::RemoveFileRequest, ::mavsdk::rpc::ftp::RemoveFileResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(6); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::RemoveFileRequest, ::mavsdk::rpc::ftp::RemoveFileResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -867,13 +690,13 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_Rename() { - ::grpc::Service::MarkMethodCallback(7, + ::grpc::Service::MarkMethodCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::RenameRequest, ::mavsdk::rpc::ftp::RenameResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::RenameRequest* request, ::mavsdk::rpc::ftp::RenameResponse* response) { return this->Rename(context, request, response); }));} void SetMessageAllocatorFor_Rename( ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::RenameRequest, ::mavsdk::rpc::ftp::RenameResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(6); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::RenameRequest, ::mavsdk::rpc::ftp::RenameResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -894,13 +717,13 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_AreFilesIdentical() { - ::grpc::Service::MarkMethodCallback(8, + ::grpc::Service::MarkMethodCallback(7, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::AreFilesIdenticalRequest, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* request, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* response) { return this->AreFilesIdentical(context, request, response); }));} void SetMessageAllocatorFor_AreFilesIdentical( ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::AreFilesIdenticalRequest, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(8); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::AreFilesIdenticalRequest, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -916,45 +739,18 @@ class FtpService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::ftp::AreFilesIdenticalRequest* /*request*/, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* /*response*/) { return nullptr; } }; template - class WithCallbackMethod_SetRootDirectory : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SetRootDirectory() { - ::grpc::Service::MarkMethodCallback(9, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* request, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* response) { return this->SetRootDirectory(context, request, response); }));} - void SetMessageAllocatorFor_SetRootDirectory( - ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(9); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_SetRootDirectory() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRootDirectory(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* /*request*/, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* SetRootDirectory( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* /*request*/, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* /*response*/) { return nullptr; } - }; - template class WithCallbackMethod_SetTargetCompid : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetTargetCompid() { - ::grpc::Service::MarkMethodCallback(10, + ::grpc::Service::MarkMethodCallback(8, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::SetTargetCompidRequest, ::mavsdk::rpc::ftp::SetTargetCompidResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* request, ::mavsdk::rpc::ftp::SetTargetCompidResponse* response) { return this->SetTargetCompid(context, request, response); }));} void SetMessageAllocatorFor_SetTargetCompid( ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::SetTargetCompidRequest, ::mavsdk::rpc::ftp::SetTargetCompidResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(10); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(8); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::SetTargetCompidRequest, ::mavsdk::rpc::ftp::SetTargetCompidResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -969,59 +765,15 @@ class FtpService final { virtual ::grpc::ServerUnaryReactor* SetTargetCompid( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetTargetCompidRequest* /*request*/, ::mavsdk::rpc::ftp::SetTargetCompidResponse* /*response*/) { return nullptr; } }; - template - class WithCallbackMethod_GetOurCompid : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_GetOurCompid() { - ::grpc::Service::MarkMethodCallback(11, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp::GetOurCompidRequest* request, ::mavsdk::rpc::ftp::GetOurCompidResponse* response) { return this->GetOurCompid(context, request, response); }));} - void SetMessageAllocatorFor_GetOurCompid( - ::grpc::MessageAllocator< ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(11); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_GetOurCompid() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status GetOurCompid(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::GetOurCompidRequest* /*request*/, ::mavsdk::rpc::ftp::GetOurCompidResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* GetOurCompid( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::ftp::GetOurCompidRequest* /*request*/, ::mavsdk::rpc::ftp::GetOurCompidResponse* /*response*/) { return nullptr; } - }; - typedef WithCallbackMethod_Reset > > > > > > > > > > > CallbackService; + typedef WithCallbackMethod_SubscribeDownload > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template - class WithGenericMethod_Reset : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_Reset() { - ::grpc::Service::MarkMethodGeneric(0); - } - ~WithGenericMethod_Reset() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Reset(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::ResetRequest* /*request*/, ::mavsdk::rpc::ftp::ResetResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template class WithGenericMethod_SubscribeDownload : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeDownload() { - ::grpc::Service::MarkMethodGeneric(1); + ::grpc::Service::MarkMethodGeneric(0); } ~WithGenericMethod_SubscribeDownload() override { BaseClassMustBeDerivedFromService(this); @@ -1038,7 +790,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeUpload() { - ::grpc::Service::MarkMethodGeneric(2); + ::grpc::Service::MarkMethodGeneric(1); } ~WithGenericMethod_SubscribeUpload() override { BaseClassMustBeDerivedFromService(this); @@ -1055,7 +807,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ListDirectory() { - ::grpc::Service::MarkMethodGeneric(3); + ::grpc::Service::MarkMethodGeneric(2); } ~WithGenericMethod_ListDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -1072,7 +824,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_CreateDirectory() { - ::grpc::Service::MarkMethodGeneric(4); + ::grpc::Service::MarkMethodGeneric(3); } ~WithGenericMethod_CreateDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -1089,7 +841,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RemoveDirectory() { - ::grpc::Service::MarkMethodGeneric(5); + ::grpc::Service::MarkMethodGeneric(4); } ~WithGenericMethod_RemoveDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -1106,7 +858,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RemoveFile() { - ::grpc::Service::MarkMethodGeneric(6); + ::grpc::Service::MarkMethodGeneric(5); } ~WithGenericMethod_RemoveFile() override { BaseClassMustBeDerivedFromService(this); @@ -1123,7 +875,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_Rename() { - ::grpc::Service::MarkMethodGeneric(7); + ::grpc::Service::MarkMethodGeneric(6); } ~WithGenericMethod_Rename() override { BaseClassMustBeDerivedFromService(this); @@ -1140,7 +892,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_AreFilesIdentical() { - ::grpc::Service::MarkMethodGeneric(8); + ::grpc::Service::MarkMethodGeneric(7); } ~WithGenericMethod_AreFilesIdentical() override { BaseClassMustBeDerivedFromService(this); @@ -1152,29 +904,12 @@ class FtpService final { } }; template - class WithGenericMethod_SetRootDirectory : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SetRootDirectory() { - ::grpc::Service::MarkMethodGeneric(9); - } - ~WithGenericMethod_SetRootDirectory() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRootDirectory(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* /*request*/, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template class WithGenericMethod_SetTargetCompid : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetTargetCompid() { - ::grpc::Service::MarkMethodGeneric(10); + ::grpc::Service::MarkMethodGeneric(8); } ~WithGenericMethod_SetTargetCompid() override { BaseClassMustBeDerivedFromService(this); @@ -1186,49 +921,12 @@ class FtpService final { } }; template - class WithGenericMethod_GetOurCompid : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_GetOurCompid() { - ::grpc::Service::MarkMethodGeneric(11); - } - ~WithGenericMethod_GetOurCompid() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status GetOurCompid(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::GetOurCompidRequest* /*request*/, ::mavsdk::rpc::ftp::GetOurCompidResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template - class WithRawMethod_Reset : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_Reset() { - ::grpc::Service::MarkMethodRaw(0); - } - ~WithRawMethod_Reset() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Reset(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::ResetRequest* /*request*/, ::mavsdk::rpc::ftp::ResetResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestReset(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template class WithRawMethod_SubscribeDownload : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeDownload() { - ::grpc::Service::MarkMethodRaw(1); + ::grpc::Service::MarkMethodRaw(0); } ~WithRawMethod_SubscribeDownload() override { BaseClassMustBeDerivedFromService(this); @@ -1239,7 +937,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeDownload(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(1, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(0, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1248,7 +946,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeUpload() { - ::grpc::Service::MarkMethodRaw(2); + ::grpc::Service::MarkMethodRaw(1); } ~WithRawMethod_SubscribeUpload() override { BaseClassMustBeDerivedFromService(this); @@ -1259,7 +957,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeUpload(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(2, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(1, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1268,7 +966,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ListDirectory() { - ::grpc::Service::MarkMethodRaw(3); + ::grpc::Service::MarkMethodRaw(2); } ~WithRawMethod_ListDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -1279,7 +977,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestListDirectory(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1288,7 +986,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_CreateDirectory() { - ::grpc::Service::MarkMethodRaw(4); + ::grpc::Service::MarkMethodRaw(3); } ~WithRawMethod_CreateDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -1299,7 +997,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestCreateDirectory(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1308,7 +1006,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RemoveDirectory() { - ::grpc::Service::MarkMethodRaw(5); + ::grpc::Service::MarkMethodRaw(4); } ~WithRawMethod_RemoveDirectory() override { BaseClassMustBeDerivedFromService(this); @@ -1319,7 +1017,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRemoveDirectory(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1328,7 +1026,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RemoveFile() { - ::grpc::Service::MarkMethodRaw(6); + ::grpc::Service::MarkMethodRaw(5); } ~WithRawMethod_RemoveFile() override { BaseClassMustBeDerivedFromService(this); @@ -1339,7 +1037,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRemoveFile(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1348,7 +1046,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_Rename() { - ::grpc::Service::MarkMethodRaw(7); + ::grpc::Service::MarkMethodRaw(6); } ~WithRawMethod_Rename() override { BaseClassMustBeDerivedFromService(this); @@ -1359,7 +1057,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRename(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1368,7 +1066,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_AreFilesIdentical() { - ::grpc::Service::MarkMethodRaw(8); + ::grpc::Service::MarkMethodRaw(7); } ~WithRawMethod_AreFilesIdentical() override { BaseClassMustBeDerivedFromService(this); @@ -1379,27 +1077,7 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestAreFilesIdentical(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_SetRootDirectory : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SetRootDirectory() { - ::grpc::Service::MarkMethodRaw(9); - } - ~WithRawMethod_SetRootDirectory() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRootDirectory(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* /*request*/, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSetRootDirectory(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1408,7 +1086,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetTargetCompid() { - ::grpc::Service::MarkMethodRaw(10); + ::grpc::Service::MarkMethodRaw(8); } ~WithRawMethod_SetTargetCompid() override { BaseClassMustBeDerivedFromService(this); @@ -1419,50 +1097,8 @@ class FtpService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetTargetCompid(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(10, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_GetOurCompid : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_GetOurCompid() { - ::grpc::Service::MarkMethodRaw(11); - } - ~WithRawMethod_GetOurCompid() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status GetOurCompid(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::GetOurCompidRequest* /*request*/, ::mavsdk::rpc::ftp::GetOurCompidResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestGetOurCompid(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(11, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawCallbackMethod_Reset : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_Reset() { - ::grpc::Service::MarkMethodRawCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->Reset(context, request, response); })); - } - ~WithRawCallbackMethod_Reset() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Reset(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::ResetRequest* /*request*/, ::mavsdk::rpc::ftp::ResetResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); } - virtual ::grpc::ServerUnaryReactor* Reset( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template class WithRawCallbackMethod_SubscribeDownload : public BaseClass { @@ -1470,7 +1106,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeDownload() { - ::grpc::Service::MarkMethodRawCallback(1, + ::grpc::Service::MarkMethodRawCallback(0, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeDownload(context, request); })); @@ -1492,7 +1128,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeUpload() { - ::grpc::Service::MarkMethodRawCallback(2, + ::grpc::Service::MarkMethodRawCallback(1, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeUpload(context, request); })); @@ -1514,7 +1150,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ListDirectory() { - ::grpc::Service::MarkMethodRawCallback(3, + ::grpc::Service::MarkMethodRawCallback(2, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ListDirectory(context, request, response); })); @@ -1536,7 +1172,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_CreateDirectory() { - ::grpc::Service::MarkMethodRawCallback(4, + ::grpc::Service::MarkMethodRawCallback(3, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->CreateDirectory(context, request, response); })); @@ -1558,7 +1194,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RemoveDirectory() { - ::grpc::Service::MarkMethodRawCallback(5, + ::grpc::Service::MarkMethodRawCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RemoveDirectory(context, request, response); })); @@ -1580,7 +1216,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RemoveFile() { - ::grpc::Service::MarkMethodRawCallback(6, + ::grpc::Service::MarkMethodRawCallback(5, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RemoveFile(context, request, response); })); @@ -1602,7 +1238,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_Rename() { - ::grpc::Service::MarkMethodRawCallback(7, + ::grpc::Service::MarkMethodRawCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->Rename(context, request, response); })); @@ -1624,7 +1260,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_AreFilesIdentical() { - ::grpc::Service::MarkMethodRawCallback(8, + ::grpc::Service::MarkMethodRawCallback(7, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->AreFilesIdentical(context, request, response); })); @@ -1641,34 +1277,12 @@ class FtpService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SetRootDirectory : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SetRootDirectory() { - ::grpc::Service::MarkMethodRawCallback(9, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRootDirectory(context, request, response); })); - } - ~WithRawCallbackMethod_SetRootDirectory() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRootDirectory(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* /*request*/, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* SetRootDirectory( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } - }; - template class WithRawCallbackMethod_SetTargetCompid : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetTargetCompid() { - ::grpc::Service::MarkMethodRawCallback(10, + ::grpc::Service::MarkMethodRawCallback(8, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetTargetCompid(context, request, response); })); @@ -1685,61 +1299,12 @@ class FtpService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_GetOurCompid : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_GetOurCompid() { - ::grpc::Service::MarkMethodRawCallback(11, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetOurCompid(context, request, response); })); - } - ~WithRawCallbackMethod_GetOurCompid() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status GetOurCompid(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::GetOurCompidRequest* /*request*/, ::mavsdk::rpc::ftp::GetOurCompidResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* GetOurCompid( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } - }; - template - class WithStreamedUnaryMethod_Reset : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_Reset() { - ::grpc::Service::MarkMethodStreamed(0, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::ftp::ResetRequest, ::mavsdk::rpc::ftp::ResetResponse>* streamer) { - return this->StreamedReset(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_Reset() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status Reset(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::ResetRequest* /*request*/, ::mavsdk::rpc::ftp::ResetResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with streamed unary - virtual ::grpc::Status StreamedReset(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::ftp::ResetRequest,::mavsdk::rpc::ftp::ResetResponse>* server_unary_streamer) = 0; - }; - template class WithStreamedUnaryMethod_ListDirectory : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ListDirectory() { - ::grpc::Service::MarkMethodStreamed(3, + ::grpc::Service::MarkMethodStreamed(2, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::ftp::ListDirectoryRequest, ::mavsdk::rpc::ftp::ListDirectoryResponse>( [this](::grpc::ServerContext* context, @@ -1766,7 +1331,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_CreateDirectory() { - ::grpc::Service::MarkMethodStreamed(4, + ::grpc::Service::MarkMethodStreamed(3, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::ftp::CreateDirectoryRequest, ::mavsdk::rpc::ftp::CreateDirectoryResponse>( [this](::grpc::ServerContext* context, @@ -1793,7 +1358,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RemoveDirectory() { - ::grpc::Service::MarkMethodStreamed(5, + ::grpc::Service::MarkMethodStreamed(4, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::ftp::RemoveDirectoryRequest, ::mavsdk::rpc::ftp::RemoveDirectoryResponse>( [this](::grpc::ServerContext* context, @@ -1820,7 +1385,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RemoveFile() { - ::grpc::Service::MarkMethodStreamed(6, + ::grpc::Service::MarkMethodStreamed(5, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::ftp::RemoveFileRequest, ::mavsdk::rpc::ftp::RemoveFileResponse>( [this](::grpc::ServerContext* context, @@ -1847,7 +1412,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_Rename() { - ::grpc::Service::MarkMethodStreamed(7, + ::grpc::Service::MarkMethodStreamed(6, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::ftp::RenameRequest, ::mavsdk::rpc::ftp::RenameResponse>( [this](::grpc::ServerContext* context, @@ -1874,7 +1439,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_AreFilesIdentical() { - ::grpc::Service::MarkMethodStreamed(8, + ::grpc::Service::MarkMethodStreamed(7, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::ftp::AreFilesIdenticalRequest, ::mavsdk::rpc::ftp::AreFilesIdenticalResponse>( [this](::grpc::ServerContext* context, @@ -1896,39 +1461,12 @@ class FtpService final { virtual ::grpc::Status StreamedAreFilesIdentical(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::ftp::AreFilesIdenticalRequest,::mavsdk::rpc::ftp::AreFilesIdenticalResponse>* server_unary_streamer) = 0; }; template - class WithStreamedUnaryMethod_SetRootDirectory : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_SetRootDirectory() { - ::grpc::Service::MarkMethodStreamed(9, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::ftp::SetRootDirectoryRequest, ::mavsdk::rpc::ftp::SetRootDirectoryResponse>* streamer) { - return this->StreamedSetRootDirectory(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_SetRootDirectory() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SetRootDirectory(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::SetRootDirectoryRequest* /*request*/, ::mavsdk::rpc::ftp::SetRootDirectoryResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with streamed unary - virtual ::grpc::Status StreamedSetRootDirectory(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::ftp::SetRootDirectoryRequest,::mavsdk::rpc::ftp::SetRootDirectoryResponse>* server_unary_streamer) = 0; - }; - template class WithStreamedUnaryMethod_SetTargetCompid : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetTargetCompid() { - ::grpc::Service::MarkMethodStreamed(10, + ::grpc::Service::MarkMethodStreamed(8, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::ftp::SetTargetCompidRequest, ::mavsdk::rpc::ftp::SetTargetCompidResponse>( [this](::grpc::ServerContext* context, @@ -1949,41 +1487,14 @@ class FtpService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedSetTargetCompid(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::ftp::SetTargetCompidRequest,::mavsdk::rpc::ftp::SetTargetCompidResponse>* server_unary_streamer) = 0; }; - template - class WithStreamedUnaryMethod_GetOurCompid : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_GetOurCompid() { - ::grpc::Service::MarkMethodStreamed(11, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::ftp::GetOurCompidRequest, ::mavsdk::rpc::ftp::GetOurCompidResponse>* streamer) { - return this->StreamedGetOurCompid(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_GetOurCompid() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status GetOurCompid(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp::GetOurCompidRequest* /*request*/, ::mavsdk::rpc::ftp::GetOurCompidResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with streamed unary - virtual ::grpc::Status StreamedGetOurCompid(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::ftp::GetOurCompidRequest,::mavsdk::rpc::ftp::GetOurCompidResponse>* server_unary_streamer) = 0; - }; - typedef WithStreamedUnaryMethod_Reset > > > > > > > > > StreamedUnaryService; + typedef WithStreamedUnaryMethod_ListDirectory > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeDownload : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeDownload() { - ::grpc::Service::MarkMethodStreamed(1, + ::grpc::Service::MarkMethodStreamed(0, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::ftp::SubscribeDownloadRequest, ::mavsdk::rpc::ftp::DownloadResponse>( [this](::grpc::ServerContext* context, @@ -2010,7 +1521,7 @@ class FtpService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeUpload() { - ::grpc::Service::MarkMethodStreamed(2, + ::grpc::Service::MarkMethodStreamed(1, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::ftp::SubscribeUploadRequest, ::mavsdk::rpc::ftp::UploadResponse>( [this](::grpc::ServerContext* context, @@ -2032,7 +1543,7 @@ class FtpService final { virtual ::grpc::Status StreamedSubscribeUpload(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::ftp::SubscribeUploadRequest,::mavsdk::rpc::ftp::UploadResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeDownload > SplitStreamedService; - typedef WithStreamedUnaryMethod_Reset > > > > > > > > > > > StreamedService; + typedef WithSplitStreamingMethod_SubscribeDownload > > > > > > > > StreamedService; }; } // namespace ftp diff --git a/src/mavsdk_server/src/generated/ftp/ftp.pb.cc b/src/mavsdk_server/src/generated/ftp/ftp.pb.cc index 0c10cc560a..2a65057af3 100644 --- a/src/mavsdk_server/src/generated/ftp/ftp.pb.cc +++ b/src/mavsdk_server/src/generated/ftp/ftp.pb.cc @@ -22,35 +22,6 @@ namespace mavsdk { namespace rpc { namespace ftp { template -PROTOBUF_CONSTEXPR ResetRequest::ResetRequest( - ::_pbi::ConstantInitialized) {} -struct ResetRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR ResetRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ResetRequestDefaultTypeInternal() {} - union { - ResetRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ResetRequestDefaultTypeInternal _ResetRequest_default_instance_; -template -PROTOBUF_CONSTEXPR ResetResponse::ResetResponse( - ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_._has_bits_)*/{} - , /*decltype(_impl_._cached_size_)*/{} - , /*decltype(_impl_.ftp_result_)*/nullptr} {} -struct ResetResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR ResetResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ResetResponseDefaultTypeInternal() {} - union { - ResetResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ResetResponseDefaultTypeInternal _ResetResponse_default_instance_; -template PROTOBUF_CONSTEXPR SubscribeDownloadRequest::SubscribeDownloadRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_.remote_file_path_)*/ { @@ -61,6 +32,8 @@ PROTOBUF_CONSTEXPR SubscribeDownloadRequest::SubscribeDownloadRequest( &::_pbi::fixed_address_empty_string, ::_pbi::ConstantInitialized {} } + , /*decltype(_impl_.use_burst_)*/ false + , /*decltype(_impl_._cached_size_)*/{}} {} struct SubscribeDownloadRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR SubscribeDownloadRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} @@ -344,40 +317,6 @@ struct AreFilesIdenticalResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 AreFilesIdenticalResponseDefaultTypeInternal _AreFilesIdenticalResponse_default_instance_; template -PROTOBUF_CONSTEXPR SetRootDirectoryRequest::SetRootDirectoryRequest( - ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_.root_dir_)*/ { - &::_pbi::fixed_address_empty_string, ::_pbi::ConstantInitialized {} - } - - , /*decltype(_impl_._cached_size_)*/{}} {} -struct SetRootDirectoryRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetRootDirectoryRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetRootDirectoryRequestDefaultTypeInternal() {} - union { - SetRootDirectoryRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRootDirectoryRequestDefaultTypeInternal _SetRootDirectoryRequest_default_instance_; -template -PROTOBUF_CONSTEXPR SetRootDirectoryResponse::SetRootDirectoryResponse( - ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_._has_bits_)*/{} - , /*decltype(_impl_._cached_size_)*/{} - , /*decltype(_impl_.ftp_result_)*/nullptr} {} -struct SetRootDirectoryResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetRootDirectoryResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetRootDirectoryResponseDefaultTypeInternal() {} - union { - SetRootDirectoryResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRootDirectoryResponseDefaultTypeInternal _SetRootDirectoryResponse_default_instance_; -template PROTOBUF_CONSTEXPR SetTargetCompidRequest::SetTargetCompidRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_.compid_)*/ 0u @@ -410,35 +349,6 @@ struct SetTargetCompidResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetTargetCompidResponseDefaultTypeInternal _SetTargetCompidResponse_default_instance_; template -PROTOBUF_CONSTEXPR GetOurCompidRequest::GetOurCompidRequest( - ::_pbi::ConstantInitialized) {} -struct GetOurCompidRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR GetOurCompidRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~GetOurCompidRequestDefaultTypeInternal() {} - union { - GetOurCompidRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetOurCompidRequestDefaultTypeInternal _GetOurCompidRequest_default_instance_; -template -PROTOBUF_CONSTEXPR GetOurCompidResponse::GetOurCompidResponse( - ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_.compid_)*/ 0u - - , /*decltype(_impl_._cached_size_)*/{}} {} -struct GetOurCompidResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR GetOurCompidResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~GetOurCompidResponseDefaultTypeInternal() {} - union { - GetOurCompidResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetOurCompidResponseDefaultTypeInternal _GetOurCompidResponse_default_instance_; -template PROTOBUF_CONSTEXPR ProgressData::ProgressData( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_.bytes_transferred_)*/ 0u @@ -479,31 +389,13 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace ftp } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_ftp_2fftp_2eproto[26]; +static ::_pb::Metadata file_level_metadata_ftp_2fftp_2eproto[20]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_ftp_2fftp_2eproto[1]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_ftp_2fftp_2eproto = nullptr; const ::uint32_t TableStruct_ftp_2fftp_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( protodesc_cold) = { ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::ResetRequest, _internal_metadata_), - ~0u, // no _extensions_ - ~0u, // no _oneof_case_ - ~0u, // no _weak_field_map_ - ~0u, // no _inlined_string_donated_ - ~0u, // no _split_ - ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::ResetResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::ResetResponse, _internal_metadata_), - ~0u, // no _extensions_ - ~0u, // no _oneof_case_ - ~0u, // no _weak_field_map_ - ~0u, // no _inlined_string_donated_ - ~0u, // no _split_ - ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::ResetResponse, _impl_.ftp_result_), - 0, - ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SubscribeDownloadRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -513,6 +405,7 @@ const ::uint32_t TableStruct_ftp_2fftp_2eproto::offsets[] PROTOBUF_SECTION_VARIA ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SubscribeDownloadRequest, _impl_.remote_file_path_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SubscribeDownloadRequest, _impl_.local_dir_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SubscribeDownloadRequest, _impl_.use_burst_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::DownloadResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::DownloadResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -668,25 +561,6 @@ const ::uint32_t TableStruct_ftp_2fftp_2eproto::offsets[] PROTOBUF_SECTION_VARIA 0, ~0u, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SetRootDirectoryRequest, _internal_metadata_), - ~0u, // no _extensions_ - ~0u, // no _oneof_case_ - ~0u, // no _weak_field_map_ - ~0u, // no _inlined_string_donated_ - ~0u, // no _split_ - ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SetRootDirectoryRequest, _impl_.root_dir_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SetRootDirectoryResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SetRootDirectoryResponse, _internal_metadata_), - ~0u, // no _extensions_ - ~0u, // no _oneof_case_ - ~0u, // no _weak_field_map_ - ~0u, // no _inlined_string_donated_ - ~0u, // no _split_ - ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SetRootDirectoryResponse, _impl_.ftp_result_), - 0, - ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SetTargetCompidRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -706,23 +580,6 @@ const ::uint32_t TableStruct_ftp_2fftp_2eproto::offsets[] PROTOBUF_SECTION_VARIA PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::SetTargetCompidResponse, _impl_.ftp_result_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::GetOurCompidRequest, _internal_metadata_), - ~0u, // no _extensions_ - ~0u, // no _oneof_case_ - ~0u, // no _weak_field_map_ - ~0u, // no _inlined_string_donated_ - ~0u, // no _split_ - ~0u, // no sizeof(Split) - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::GetOurCompidResponse, _internal_metadata_), - ~0u, // no _extensions_ - ~0u, // no _oneof_case_ - ~0u, // no _weak_field_map_ - ~0u, // no _inlined_string_donated_ - ~0u, // no _split_ - ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::GetOurCompidResponse, _impl_.compid_), - ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp::ProgressData, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -746,37 +603,29 @@ const ::uint32_t TableStruct_ftp_2fftp_2eproto::offsets[] PROTOBUF_SECTION_VARIA static const ::_pbi::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { - { 0, -1, -1, sizeof(::mavsdk::rpc::ftp::ResetRequest)}, - { 8, 17, -1, sizeof(::mavsdk::rpc::ftp::ResetResponse)}, - { 18, -1, -1, sizeof(::mavsdk::rpc::ftp::SubscribeDownloadRequest)}, - { 28, 38, -1, sizeof(::mavsdk::rpc::ftp::DownloadResponse)}, - { 40, -1, -1, sizeof(::mavsdk::rpc::ftp::SubscribeUploadRequest)}, - { 50, 60, -1, sizeof(::mavsdk::rpc::ftp::UploadResponse)}, - { 62, -1, -1, sizeof(::mavsdk::rpc::ftp::ListDirectoryRequest)}, - { 71, 81, -1, sizeof(::mavsdk::rpc::ftp::ListDirectoryResponse)}, - { 83, -1, -1, sizeof(::mavsdk::rpc::ftp::CreateDirectoryRequest)}, - { 92, 101, -1, sizeof(::mavsdk::rpc::ftp::CreateDirectoryResponse)}, - { 102, -1, -1, sizeof(::mavsdk::rpc::ftp::RemoveDirectoryRequest)}, - { 111, 120, -1, sizeof(::mavsdk::rpc::ftp::RemoveDirectoryResponse)}, - { 121, -1, -1, sizeof(::mavsdk::rpc::ftp::RemoveFileRequest)}, - { 130, 139, -1, sizeof(::mavsdk::rpc::ftp::RemoveFileResponse)}, - { 140, -1, -1, sizeof(::mavsdk::rpc::ftp::RenameRequest)}, - { 150, 159, -1, sizeof(::mavsdk::rpc::ftp::RenameResponse)}, - { 160, -1, -1, sizeof(::mavsdk::rpc::ftp::AreFilesIdenticalRequest)}, - { 170, 180, -1, sizeof(::mavsdk::rpc::ftp::AreFilesIdenticalResponse)}, - { 182, -1, -1, sizeof(::mavsdk::rpc::ftp::SetRootDirectoryRequest)}, - { 191, 200, -1, sizeof(::mavsdk::rpc::ftp::SetRootDirectoryResponse)}, - { 201, -1, -1, sizeof(::mavsdk::rpc::ftp::SetTargetCompidRequest)}, - { 210, 219, -1, sizeof(::mavsdk::rpc::ftp::SetTargetCompidResponse)}, - { 220, -1, -1, sizeof(::mavsdk::rpc::ftp::GetOurCompidRequest)}, - { 228, -1, -1, sizeof(::mavsdk::rpc::ftp::GetOurCompidResponse)}, - { 237, -1, -1, sizeof(::mavsdk::rpc::ftp::ProgressData)}, - { 247, -1, -1, sizeof(::mavsdk::rpc::ftp::FtpResult)}, + { 0, -1, -1, sizeof(::mavsdk::rpc::ftp::SubscribeDownloadRequest)}, + { 11, 21, -1, sizeof(::mavsdk::rpc::ftp::DownloadResponse)}, + { 23, -1, -1, sizeof(::mavsdk::rpc::ftp::SubscribeUploadRequest)}, + { 33, 43, -1, sizeof(::mavsdk::rpc::ftp::UploadResponse)}, + { 45, -1, -1, sizeof(::mavsdk::rpc::ftp::ListDirectoryRequest)}, + { 54, 64, -1, sizeof(::mavsdk::rpc::ftp::ListDirectoryResponse)}, + { 66, -1, -1, sizeof(::mavsdk::rpc::ftp::CreateDirectoryRequest)}, + { 75, 84, -1, sizeof(::mavsdk::rpc::ftp::CreateDirectoryResponse)}, + { 85, -1, -1, sizeof(::mavsdk::rpc::ftp::RemoveDirectoryRequest)}, + { 94, 103, -1, sizeof(::mavsdk::rpc::ftp::RemoveDirectoryResponse)}, + { 104, -1, -1, sizeof(::mavsdk::rpc::ftp::RemoveFileRequest)}, + { 113, 122, -1, sizeof(::mavsdk::rpc::ftp::RemoveFileResponse)}, + { 123, -1, -1, sizeof(::mavsdk::rpc::ftp::RenameRequest)}, + { 133, 142, -1, sizeof(::mavsdk::rpc::ftp::RenameResponse)}, + { 143, -1, -1, sizeof(::mavsdk::rpc::ftp::AreFilesIdenticalRequest)}, + { 153, 163, -1, sizeof(::mavsdk::rpc::ftp::AreFilesIdenticalResponse)}, + { 165, -1, -1, sizeof(::mavsdk::rpc::ftp::SetTargetCompidRequest)}, + { 174, 183, -1, sizeof(::mavsdk::rpc::ftp::SetTargetCompidResponse)}, + { 184, -1, -1, sizeof(::mavsdk::rpc::ftp::ProgressData)}, + { 194, -1, -1, sizeof(::mavsdk::rpc::ftp::FtpResult)}, }; static const ::_pb::Message* const file_default_instances[] = { - &::mavsdk::rpc::ftp::_ResetRequest_default_instance_._instance, - &::mavsdk::rpc::ftp::_ResetResponse_default_instance_._instance, &::mavsdk::rpc::ftp::_SubscribeDownloadRequest_default_instance_._instance, &::mavsdk::rpc::ftp::_DownloadResponse_default_instance_._instance, &::mavsdk::rpc::ftp::_SubscribeUploadRequest_default_instance_._instance, @@ -793,71 +642,59 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::ftp::_RenameResponse_default_instance_._instance, &::mavsdk::rpc::ftp::_AreFilesIdenticalRequest_default_instance_._instance, &::mavsdk::rpc::ftp::_AreFilesIdenticalResponse_default_instance_._instance, - &::mavsdk::rpc::ftp::_SetRootDirectoryRequest_default_instance_._instance, - &::mavsdk::rpc::ftp::_SetRootDirectoryResponse_default_instance_._instance, &::mavsdk::rpc::ftp::_SetTargetCompidRequest_default_instance_._instance, &::mavsdk::rpc::ftp::_SetTargetCompidResponse_default_instance_._instance, - &::mavsdk::rpc::ftp::_GetOurCompidRequest_default_instance_._instance, - &::mavsdk::rpc::ftp::_GetOurCompidResponse_default_instance_._instance, &::mavsdk::rpc::ftp::_ProgressData_default_instance_._instance, &::mavsdk::rpc::ftp::_FtpResult_default_instance_._instance, }; const char descriptor_table_protodef_ftp_2fftp_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { "\n\rftp/ftp.proto\022\016mavsdk.rpc.ftp\032\024mavsdk_" - "options.proto\"\016\n\014ResetRequest\">\n\rResetRe" - "sponse\022-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc." - "ftp.FtpResult\"G\n\030SubscribeDownloadReques" + "options.proto\"Z\n\030SubscribeDownloadReques" "t\022\030\n\020remote_file_path\030\001 \001(\t\022\021\n\tlocal_dir" - "\030\002 \001(\t\"v\n\020DownloadResponse\022-\n\nftp_result" - "\030\001 \001(\0132\031.mavsdk.rpc.ftp.FtpResult\0223\n\rpro" - "gress_data\030\002 \001(\0132\034.mavsdk.rpc.ftp.Progre" - "ssData\"E\n\026SubscribeUploadRequest\022\027\n\017loca" - "l_file_path\030\001 \001(\t\022\022\n\nremote_dir\030\002 \001(\t\"t\n" - "\016UploadResponse\022-\n\nftp_result\030\001 \001(\0132\031.ma" - "vsdk.rpc.ftp.FtpResult\0223\n\rprogress_data\030" - "\002 \001(\0132\034.mavsdk.rpc.ftp.ProgressData\"*\n\024L" - "istDirectoryRequest\022\022\n\nremote_dir\030\001 \001(\t\"" - "U\n\025ListDirectoryResponse\022-\n\nftp_result\030\001" - " \001(\0132\031.mavsdk.rpc.ftp.FtpResult\022\r\n\005paths" - "\030\002 \003(\t\",\n\026CreateDirectoryRequest\022\022\n\nremo" - "te_dir\030\001 \001(\t\"H\n\027CreateDirectoryResponse\022" - "-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc.ftp.Ftp" - "Result\",\n\026RemoveDirectoryRequest\022\022\n\nremo" - "te_dir\030\001 \001(\t\"H\n\027RemoveDirectoryResponse\022" - "-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc.ftp.Ftp" - "Result\"-\n\021RemoveFileRequest\022\030\n\020remote_fi" - "le_path\030\001 \001(\t\"C\n\022RemoveFileResponse\022-\n\nf" - "tp_result\030\001 \001(\0132\031.mavsdk.rpc.ftp.FtpResu" - "lt\"A\n\rRenameRequest\022\030\n\020remote_from_path\030" - "\001 \001(\t\022\026\n\016remote_to_path\030\002 \001(\t\"\?\n\016RenameR" - "esponse\022-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc" - ".ftp.FtpResult\"M\n\030AreFilesIdenticalReque" - "st\022\027\n\017local_file_path\030\001 \001(\t\022\030\n\020remote_fi" - "le_path\030\002 \001(\t\"a\n\031AreFilesIdenticalRespon" - "se\022-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc.ftp." - "FtpResult\022\025\n\rare_identical\030\002 \001(\010\"+\n\027SetR" - "ootDirectoryRequest\022\020\n\010root_dir\030\001 \001(\t\"I\n" - "\030SetRootDirectoryResponse\022-\n\nftp_result\030" - "\001 \001(\0132\031.mavsdk.rpc.ftp.FtpResult\"(\n\026SetT" - "argetCompidRequest\022\016\n\006compid\030\001 \001(\r\"H\n\027Se" - "tTargetCompidResponse\022-\n\nftp_result\030\001 \001(" - "\0132\031.mavsdk.rpc.ftp.FtpResult\"\025\n\023GetOurCo" - "mpidRequest\"&\n\024GetOurCompidResponse\022\016\n\006c" - "ompid\030\001 \001(\r\">\n\014ProgressData\022\031\n\021bytes_tra" - "nsferred\030\001 \001(\r\022\023\n\013total_bytes\030\002 \001(\r\"\216\003\n\t" - "FtpResult\0220\n\006result\030\001 \001(\0162 .mavsdk.rpc.f" - "tp.FtpResult.Result\022\022\n\nresult_str\030\002 \001(\t\"" - "\272\002\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT" - "_SUCCESS\020\001\022\017\n\013RESULT_NEXT\020\002\022\022\n\016RESULT_TI" - "MEOUT\020\003\022\017\n\013RESULT_BUSY\020\004\022\030\n\024RESULT_FILE_" - "IO_ERROR\020\005\022\026\n\022RESULT_FILE_EXISTS\020\006\022\036\n\032RE" - "SULT_FILE_DOES_NOT_EXIST\020\007\022\031\n\025RESULT_FIL" - "E_PROTECTED\020\010\022\034\n\030RESULT_INVALID_PARAMETE" - "R\020\t\022\026\n\022RESULT_UNSUPPORTED\020\n\022\031\n\025RESULT_PR" - "OTOCOL_ERROR\020\013\022\024\n\020RESULT_NO_SYSTEM\020\0142\236\t\n" - "\nFtpService\022J\n\005Reset\022\034.mavsdk.rpc.ftp.Re" - "setRequest\032\035.mavsdk.rpc.ftp.ResetRespons" - "e\"\004\200\265\030\000\022k\n\021SubscribeDownload\022(.mavsdk.rp" + "\030\002 \001(\t\022\021\n\tuse_burst\030\003 \001(\010\"v\n\020DownloadRes" + "ponse\022-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc.f" + "tp.FtpResult\0223\n\rprogress_data\030\002 \001(\0132\034.ma" + "vsdk.rpc.ftp.ProgressData\"E\n\026SubscribeUp" + "loadRequest\022\027\n\017local_file_path\030\001 \001(\t\022\022\n\n" + "remote_dir\030\002 \001(\t\"t\n\016UploadResponse\022-\n\nft" + "p_result\030\001 \001(\0132\031.mavsdk.rpc.ftp.FtpResul" + "t\0223\n\rprogress_data\030\002 \001(\0132\034.mavsdk.rpc.ft" + "p.ProgressData\"*\n\024ListDirectoryRequest\022\022" + "\n\nremote_dir\030\001 \001(\t\"U\n\025ListDirectoryRespo" + "nse\022-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc.ftp" + ".FtpResult\022\r\n\005paths\030\002 \003(\t\",\n\026CreateDirec" + "toryRequest\022\022\n\nremote_dir\030\001 \001(\t\"H\n\027Creat" + "eDirectoryResponse\022-\n\nftp_result\030\001 \001(\0132\031" + ".mavsdk.rpc.ftp.FtpResult\",\n\026RemoveDirec" + "toryRequest\022\022\n\nremote_dir\030\001 \001(\t\"H\n\027Remov" + "eDirectoryResponse\022-\n\nftp_result\030\001 \001(\0132\031" + ".mavsdk.rpc.ftp.FtpResult\"-\n\021RemoveFileR" + "equest\022\030\n\020remote_file_path\030\001 \001(\t\"C\n\022Remo" + "veFileResponse\022-\n\nftp_result\030\001 \001(\0132\031.mav" + "sdk.rpc.ftp.FtpResult\"A\n\rRenameRequest\022\030" + "\n\020remote_from_path\030\001 \001(\t\022\026\n\016remote_to_pa" + "th\030\002 \001(\t\"\?\n\016RenameResponse\022-\n\nftp_result" + "\030\001 \001(\0132\031.mavsdk.rpc.ftp.FtpResult\"M\n\030Are" + "FilesIdenticalRequest\022\027\n\017local_file_path" + "\030\001 \001(\t\022\030\n\020remote_file_path\030\002 \001(\t\"a\n\031AreF" + "ilesIdenticalResponse\022-\n\nftp_result\030\001 \001(" + "\0132\031.mavsdk.rpc.ftp.FtpResult\022\025\n\rare_iden" + "tical\030\002 \001(\010\"(\n\026SetTargetCompidRequest\022\016\n" + "\006compid\030\001 \001(\r\"H\n\027SetTargetCompidResponse" + "\022-\n\nftp_result\030\001 \001(\0132\031.mavsdk.rpc.ftp.Ft" + "pResult\">\n\014ProgressData\022\031\n\021bytes_transfe" + "rred\030\001 \001(\r\022\023\n\013total_bytes\030\002 \001(\r\"\216\003\n\tFtpR" + "esult\0220\n\006result\030\001 \001(\0162 .mavsdk.rpc.ftp.F" + "tpResult.Result\022\022\n\nresult_str\030\002 \001(\t\"\272\002\n\006" + "Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUC" + "CESS\020\001\022\017\n\013RESULT_NEXT\020\002\022\022\n\016RESULT_TIMEOU" + "T\020\003\022\017\n\013RESULT_BUSY\020\004\022\030\n\024RESULT_FILE_IO_E" + "RROR\020\005\022\026\n\022RESULT_FILE_EXISTS\020\006\022\036\n\032RESULT" + "_FILE_DOES_NOT_EXIST\020\007\022\031\n\025RESULT_FILE_PR" + "OTECTED\020\010\022\034\n\030RESULT_INVALID_PARAMETER\020\t\022" + "\026\n\022RESULT_UNSUPPORTED\020\n\022\031\n\025RESULT_PROTOC" + "OL_ERROR\020\013\022\024\n\020RESULT_NO_SYSTEM\020\0142\204\007\n\nFtp" + "Service\022k\n\021SubscribeDownload\022(.mavsdk.rp" "c.ftp.SubscribeDownloadRequest\032 .mavsdk." "rpc.ftp.DownloadResponse\"\010\200\265\030\000\210\265\030\0010\001\022e\n\017" "SubscribeUpload\022&.mavsdk.rpc.ftp.Subscri" @@ -876,16 +713,11 @@ const char descriptor_table_protodef_ftp_2fftp_2eproto[] PROTOBUF_SECTION_VARIAB "Request\032\036.mavsdk.rpc.ftp.RenameResponse\"" "\000\022j\n\021AreFilesIdentical\022(.mavsdk.rpc.ftp." "AreFilesIdenticalRequest\032).mavsdk.rpc.ft" - "p.AreFilesIdenticalResponse\"\000\022k\n\020SetRoot" - "Directory\022\'.mavsdk.rpc.ftp.SetRootDirect" - "oryRequest\032(.mavsdk.rpc.ftp.SetRootDirec" - "toryResponse\"\004\200\265\030\001\022h\n\017SetTargetCompid\022&." - "mavsdk.rpc.ftp.SetTargetCompidRequest\032\'." - "mavsdk.rpc.ftp.SetTargetCompidResponse\"\004" - "\200\265\030\001\022_\n\014GetOurCompid\022#.mavsdk.rpc.ftp.Ge" - "tOurCompidRequest\032$.mavsdk.rpc.ftp.GetOu" - "rCompidResponse\"\004\200\265\030\001B\031\n\rio.mavsdk.ftpB\010" - "FtpProtob\006proto3" + "p.AreFilesIdenticalResponse\"\000\022h\n\017SetTarg" + "etCompid\022&.mavsdk.rpc.ftp.SetTargetCompi" + "dRequest\032\'.mavsdk.rpc.ftp.SetTargetCompi" + "dResponse\"\004\200\265\030\001B\031\n\rio.mavsdk.ftpB\010FtpPro" + "tob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_ftp_2fftp_2eproto_deps[1] = { @@ -895,13 +727,13 @@ static ::absl::once_flag descriptor_table_ftp_2fftp_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_ftp_2fftp_2eproto = { false, false, - 3296, + 2770, descriptor_table_protodef_ftp_2fftp_2eproto, "ftp/ftp.proto", &descriptor_table_ftp_2fftp_2eproto_once, descriptor_table_ftp_2fftp_2eproto_deps, 1, - 26, + 20, schemas, file_default_instances, TableStruct_ftp_2fftp_2eproto::offsets, @@ -978,90 +810,69 @@ constexpr int FtpResult::Result_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) // =================================================================== -class ResetRequest::_Internal { - public: -}; - -ResetRequest::ResetRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.ResetRequest) -} -ResetRequest::ResetRequest(const ResetRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - ResetRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.ResetRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ResetRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ResetRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata ResetRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[0]); -} -// =================================================================== - -class ResetResponse::_Internal { +class SubscribeDownloadRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ResetResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::ftp::FtpResult& ftp_result(const ResetResponse* msg); - static void set_has_ftp_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::ftp::FtpResult& -ResetResponse::_Internal::ftp_result(const ResetResponse* msg) { - return *msg->_impl_.ftp_result_; -} -ResetResponse::ResetResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +SubscribeDownloadRequest::SubscribeDownloadRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.ResetResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.SubscribeDownloadRequest) } -ResetResponse::ResetResponse(const ResetResponse& from) +SubscribeDownloadRequest::SubscribeDownloadRequest(const SubscribeDownloadRequest& from) : ::PROTOBUF_NAMESPACE_ID::Message() { - ResetResponse* const _this = this; (void)_this; + SubscribeDownloadRequest* const _this = this; (void)_this; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.ftp_result_){nullptr}}; + decltype(_impl_.remote_file_path_) {} + + , decltype(_impl_.local_dir_) {} + + , decltype(_impl_.use_burst_) {} + + , /*decltype(_impl_._cached_size_)*/{}}; _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.ftp_result_ = new ::mavsdk::rpc::ftp::FtpResult(*from._impl_.ftp_result_); + _impl_.remote_file_path_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.remote_file_path_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_remote_file_path().empty()) { + _this->_impl_.remote_file_path_.Set(from._internal_remote_file_path(), _this->GetArenaForAllocation()); + } + _impl_.local_dir_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.local_dir_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_local_dir().empty()) { + _this->_impl_.local_dir_.Set(from._internal_local_dir(), _this->GetArenaForAllocation()); } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.ResetResponse) + _this->_impl_.use_burst_ = from._impl_.use_burst_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.SubscribeDownloadRequest) } -inline void ResetResponse::SharedCtor(::_pb::Arena* arena) { +inline void SubscribeDownloadRequest::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} + decltype(_impl_.remote_file_path_) {} + + , decltype(_impl_.local_dir_) {} + + , decltype(_impl_.use_burst_) { false } + , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.ftp_result_){nullptr} }; + _impl_.remote_file_path_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.remote_file_path_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.local_dir_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.local_dir_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING } -ResetResponse::~ResetResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.ResetResponse) +SubscribeDownloadRequest::~SubscribeDownloadRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.SubscribeDownloadRequest) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -1069,41 +880,60 @@ ResetResponse::~ResetResponse() { SharedDtor(); } -inline void ResetResponse::SharedDtor() { +inline void SubscribeDownloadRequest::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.ftp_result_; + _impl_.remote_file_path_.Destroy(); + _impl_.local_dir_.Destroy(); } -void ResetResponse::SetCachedSize(int size) const { +void SubscribeDownloadRequest::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void ResetResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.ResetResponse) +void SubscribeDownloadRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.SubscribeDownloadRequest) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.ftp_result_ != nullptr); - _impl_.ftp_result_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.remote_file_path_.ClearToEmpty(); + _impl_.local_dir_.ClearToEmpty(); + _impl_.use_burst_ = false; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* ResetResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* SubscribeDownloadRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; + // string remote_file_path = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - ptr = ctx->ParseMessage(_internal_mutable_ftp_result(), ptr); + auto str = _internal_mutable_remote_file_path(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.ftp.SubscribeDownloadRequest.remote_file_path")); + } else { + goto handle_unusual; + } + continue; + // string local_dir = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + auto str = _internal_mutable_local_dir(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.ftp.SubscribeDownloadRequest.local_dir")); + } else { + goto handle_unusual; + } + continue; + // bool use_burst = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 24)) { + _impl_.use_burst_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); CHK_(ptr); } else { goto handle_unusual; @@ -1125,7 +955,6 @@ const char* ResetResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* CHK_(ptr != nullptr); } // while message_done: - _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -1133,279 +962,66 @@ const char* ResetResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* #undef CHK_ } -::uint8_t* ResetResponse::_InternalSerialize( +::uint8_t* SubscribeDownloadRequest::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.ResetResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.SubscribeDownloadRequest) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(1, _Internal::ftp_result(this), - _Internal::ftp_result(this).GetCachedSize(), target, stream); + // string remote_file_path = 1; + if (!this->_internal_remote_file_path().empty()) { + const std::string& _s = this->_internal_remote_file_path(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.ftp.SubscribeDownloadRequest.remote_file_path"); + target = stream->WriteStringMaybeAliased(1, _s, target); + } + + // string local_dir = 2; + if (!this->_internal_local_dir().empty()) { + const std::string& _s = this->_internal_local_dir(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.ftp.SubscribeDownloadRequest.local_dir"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + // bool use_burst = 3; + if (this->_internal_use_burst() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 3, this->_internal_use_burst(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.ResetResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.SubscribeDownloadRequest) return target; } -::size_t ResetResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.ResetResponse) +::size_t SubscribeDownloadRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.SubscribeDownloadRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.ftp_result_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ResetResponse::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - ResetResponse::MergeImpl -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ResetResponse::GetClassData() const { return &_class_data_; } - - -void ResetResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp.ResetResponse) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_ftp_result()->::mavsdk::rpc::ftp::FtpResult::MergeFrom( - from._internal_ftp_result()); - } - _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); -} - -void ResetResponse::CopyFrom(const ResetResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp.ResetResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool ResetResponse::IsInitialized() const { - return true; -} - -void ResetResponse::InternalSwap(ResetResponse* other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.ftp_result_, other->_impl_.ftp_result_); -} - -::PROTOBUF_NAMESPACE_ID::Metadata ResetResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[1]); -} -// =================================================================== - -class SubscribeDownloadRequest::_Internal { - public: -}; - -SubscribeDownloadRequest::SubscribeDownloadRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.SubscribeDownloadRequest) -} -SubscribeDownloadRequest::SubscribeDownloadRequest(const SubscribeDownloadRequest& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - SubscribeDownloadRequest* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_.remote_file_path_) {} - - , decltype(_impl_.local_dir_) {} - - , /*decltype(_impl_._cached_size_)*/{}}; - - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - _impl_.remote_file_path_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.remote_file_path_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_remote_file_path().empty()) { - _this->_impl_.remote_file_path_.Set(from._internal_remote_file_path(), _this->GetArenaForAllocation()); - } - _impl_.local_dir_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.local_dir_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_local_dir().empty()) { - _this->_impl_.local_dir_.Set(from._internal_local_dir(), _this->GetArenaForAllocation()); - } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.SubscribeDownloadRequest) -} - -inline void SubscribeDownloadRequest::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_.remote_file_path_) {} - - , decltype(_impl_.local_dir_) {} - - , /*decltype(_impl_._cached_size_)*/{} - }; - _impl_.remote_file_path_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.remote_file_path_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.local_dir_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.local_dir_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING -} - -SubscribeDownloadRequest::~SubscribeDownloadRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.SubscribeDownloadRequest) - if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { - (void)arena; - return; - } - SharedDtor(); -} - -inline void SubscribeDownloadRequest::SharedDtor() { - ABSL_DCHECK(GetArenaForAllocation() == nullptr); - _impl_.remote_file_path_.Destroy(); - _impl_.local_dir_.Destroy(); -} - -void SubscribeDownloadRequest::SetCachedSize(int size) const { - _impl_._cached_size_.Set(size); -} - -void SubscribeDownloadRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.SubscribeDownloadRequest) - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - _impl_.remote_file_path_.ClearToEmpty(); - _impl_.local_dir_.ClearToEmpty(); - _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); -} - -const char* SubscribeDownloadRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { -#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - while (!ctx->Done(&ptr)) { - ::uint32_t tag; - ptr = ::_pbi::ReadTag(ptr, &tag); - switch (tag >> 3) { - // string remote_file_path = 1; - case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - auto str = _internal_mutable_remote_file_path(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); - CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.ftp.SubscribeDownloadRequest.remote_file_path")); - } else { - goto handle_unusual; - } - continue; - // string local_dir = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { - auto str = _internal_mutable_local_dir(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); - CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.ftp.SubscribeDownloadRequest.local_dir")); - } else { - goto handle_unusual; - } - continue; - default: - goto handle_unusual; - } // switch - handle_unusual: - if ((tag == 0) || ((tag & 7) == 4)) { - CHK_(ptr); - ctx->SetLastTag(tag); - goto message_done; - } - ptr = UnknownFieldParse( - tag, - _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), - ptr, ctx); - CHK_(ptr != nullptr); - } // while -message_done: - return ptr; -failure: - ptr = nullptr; - goto message_done; -#undef CHK_ -} - -::uint8_t* SubscribeDownloadRequest::_InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.SubscribeDownloadRequest) - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - // string remote_file_path = 1; - if (!this->_internal_remote_file_path().empty()) { - const std::string& _s = this->_internal_remote_file_path(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.ftp.SubscribeDownloadRequest.remote_file_path"); - target = stream->WriteStringMaybeAliased(1, _s, target); + // string remote_file_path = 1; + if (!this->_internal_remote_file_path().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_remote_file_path()); } // string local_dir = 2; if (!this->_internal_local_dir().empty()) { - const std::string& _s = this->_internal_local_dir(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.ftp.SubscribeDownloadRequest.local_dir"); - target = stream->WriteStringMaybeAliased(2, _s, target); - } - - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { - target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( - _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); - } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.SubscribeDownloadRequest) - return target; -} - -::size_t SubscribeDownloadRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.SubscribeDownloadRequest) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // string remote_file_path = 1; - if (!this->_internal_remote_file_path().empty()) { total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_remote_file_path()); + this->_internal_local_dir()); } - // string local_dir = 2; - if (!this->_internal_local_dir().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_local_dir()); + // bool use_burst = 3; + if (this->_internal_use_burst() != 0) { + total_size += 2; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); @@ -1432,6 +1048,9 @@ void SubscribeDownloadRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_ms if (!from._internal_local_dir().empty()) { _this->_internal_set_local_dir(from._internal_local_dir()); } + if (from._internal_use_burst() != 0) { + _this->_internal_set_use_burst(from._internal_use_burst()); + } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } @@ -1455,12 +1074,14 @@ void SubscribeDownloadRequest::InternalSwap(SubscribeDownloadRequest* other) { &other->_impl_.remote_file_path_, rhs_arena); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.local_dir_, lhs_arena, &other->_impl_.local_dir_, rhs_arena); + + swap(_impl_.use_burst_, other->_impl_.use_burst_); } ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeDownloadRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[2]); + file_level_metadata_ftp_2fftp_2eproto[0]); } // =================================================================== @@ -1722,7 +1343,7 @@ void DownloadResponse::InternalSwap(DownloadResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata DownloadResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[3]); + file_level_metadata_ftp_2fftp_2eproto[1]); } // =================================================================== @@ -1965,7 +1586,7 @@ void SubscribeUploadRequest::InternalSwap(SubscribeUploadRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeUploadRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[4]); + file_level_metadata_ftp_2fftp_2eproto[2]); } // =================================================================== @@ -2227,7 +1848,7 @@ void UploadResponse::InternalSwap(UploadResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata UploadResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[5]); + file_level_metadata_ftp_2fftp_2eproto[3]); } // =================================================================== @@ -2423,7 +2044,7 @@ void ListDirectoryRequest::InternalSwap(ListDirectoryRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata ListDirectoryRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[6]); + file_level_metadata_ftp_2fftp_2eproto[4]); } // =================================================================== @@ -2666,7 +2287,7 @@ void ListDirectoryResponse::InternalSwap(ListDirectoryResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata ListDirectoryResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[7]); + file_level_metadata_ftp_2fftp_2eproto[5]); } // =================================================================== @@ -2862,7 +2483,7 @@ void CreateDirectoryRequest::InternalSwap(CreateDirectoryRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CreateDirectoryRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[8]); + file_level_metadata_ftp_2fftp_2eproto[6]); } // =================================================================== @@ -3067,7 +2688,7 @@ void CreateDirectoryResponse::InternalSwap(CreateDirectoryResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CreateDirectoryResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[9]); + file_level_metadata_ftp_2fftp_2eproto[7]); } // =================================================================== @@ -3263,7 +2884,7 @@ void RemoveDirectoryRequest::InternalSwap(RemoveDirectoryRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RemoveDirectoryRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[10]); + file_level_metadata_ftp_2fftp_2eproto[8]); } // =================================================================== @@ -3468,7 +3089,7 @@ void RemoveDirectoryResponse::InternalSwap(RemoveDirectoryResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RemoveDirectoryResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[11]); + file_level_metadata_ftp_2fftp_2eproto[9]); } // =================================================================== @@ -3664,7 +3285,7 @@ void RemoveFileRequest::InternalSwap(RemoveFileRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RemoveFileRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[12]); + file_level_metadata_ftp_2fftp_2eproto[10]); } // =================================================================== @@ -3869,7 +3490,7 @@ void RemoveFileResponse::InternalSwap(RemoveFileResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RemoveFileResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[13]); + file_level_metadata_ftp_2fftp_2eproto[11]); } // =================================================================== @@ -4112,7 +3733,7 @@ void RenameRequest::InternalSwap(RenameRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RenameRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[14]); + file_level_metadata_ftp_2fftp_2eproto[12]); } // =================================================================== @@ -4317,7 +3938,7 @@ void RenameResponse::InternalSwap(RenameResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RenameResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[15]); + file_level_metadata_ftp_2fftp_2eproto[13]); } // =================================================================== @@ -4557,495 +4178,64 @@ void AreFilesIdenticalRequest::InternalSwap(AreFilesIdenticalRequest* other) { &other->_impl_.remote_file_path_, rhs_arena); } -::PROTOBUF_NAMESPACE_ID::Metadata AreFilesIdenticalRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[16]); -} -// =================================================================== - -class AreFilesIdenticalResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(AreFilesIdenticalResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::ftp::FtpResult& ftp_result(const AreFilesIdenticalResponse* msg); - static void set_has_ftp_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::ftp::FtpResult& -AreFilesIdenticalResponse::_Internal::ftp_result(const AreFilesIdenticalResponse* msg) { - return *msg->_impl_.ftp_result_; -} -AreFilesIdenticalResponse::AreFilesIdenticalResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.AreFilesIdenticalResponse) -} -AreFilesIdenticalResponse::AreFilesIdenticalResponse(const AreFilesIdenticalResponse& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - AreFilesIdenticalResponse* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.ftp_result_){nullptr} - , decltype(_impl_.are_identical_) {} - }; - - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.ftp_result_ = new ::mavsdk::rpc::ftp::FtpResult(*from._impl_.ftp_result_); - } - _this->_impl_.are_identical_ = from._impl_.are_identical_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.AreFilesIdenticalResponse) -} - -inline void AreFilesIdenticalResponse::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.ftp_result_){nullptr} - , decltype(_impl_.are_identical_) { false } - - }; -} - -AreFilesIdenticalResponse::~AreFilesIdenticalResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.AreFilesIdenticalResponse) - if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { - (void)arena; - return; - } - SharedDtor(); -} - -inline void AreFilesIdenticalResponse::SharedDtor() { - ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.ftp_result_; -} - -void AreFilesIdenticalResponse::SetCachedSize(int size) const { - _impl_._cached_size_.Set(size); -} - -void AreFilesIdenticalResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.ftp_result_ != nullptr); - _impl_.ftp_result_->Clear(); - } - _impl_.are_identical_ = false; - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); -} - -const char* AreFilesIdenticalResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { -#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; - while (!ctx->Done(&ptr)) { - ::uint32_t tag; - ptr = ::_pbi::ReadTag(ptr, &tag); - switch (tag >> 3) { - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - ptr = ctx->ParseMessage(_internal_mutable_ftp_result(), ptr); - CHK_(ptr); - } else { - goto handle_unusual; - } - continue; - // bool are_identical = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 16)) { - _impl_.are_identical_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); - CHK_(ptr); - } else { - goto handle_unusual; - } - continue; - default: - goto handle_unusual; - } // switch - handle_unusual: - if ((tag == 0) || ((tag & 7) == 4)) { - CHK_(ptr); - ctx->SetLastTag(tag); - goto message_done; - } - ptr = UnknownFieldParse( - tag, - _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), - ptr, ctx); - CHK_(ptr != nullptr); - } // while -message_done: - _impl_._has_bits_.Or(has_bits); - return ptr; -failure: - ptr = nullptr; - goto message_done; -#undef CHK_ -} - -::uint8_t* AreFilesIdenticalResponse::_InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(1, _Internal::ftp_result(this), - _Internal::ftp_result(this).GetCachedSize(), target, stream); - } - - // bool are_identical = 2; - if (this->_internal_are_identical() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteBoolToArray( - 2, this->_internal_are_identical(), target); - } - - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { - target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( - _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); - } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.AreFilesIdenticalResponse) - return target; -} - -::size_t AreFilesIdenticalResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.ftp_result_); - } - - // bool are_identical = 2; - if (this->_internal_are_identical() != 0) { - total_size += 2; - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData AreFilesIdenticalResponse::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - AreFilesIdenticalResponse::MergeImpl -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*AreFilesIdenticalResponse::GetClassData() const { return &_class_data_; } - - -void AreFilesIdenticalResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_ftp_result()->::mavsdk::rpc::ftp::FtpResult::MergeFrom( - from._internal_ftp_result()); - } - if (from._internal_are_identical() != 0) { - _this->_internal_set_are_identical(from._internal_are_identical()); - } - _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); -} - -void AreFilesIdenticalResponse::CopyFrom(const AreFilesIdenticalResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool AreFilesIdenticalResponse::IsInitialized() const { - return true; -} - -void AreFilesIdenticalResponse::InternalSwap(AreFilesIdenticalResponse* other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(AreFilesIdenticalResponse, _impl_.are_identical_) - + sizeof(AreFilesIdenticalResponse::_impl_.are_identical_) - - PROTOBUF_FIELD_OFFSET(AreFilesIdenticalResponse, _impl_.ftp_result_)>( - reinterpret_cast(&_impl_.ftp_result_), - reinterpret_cast(&other->_impl_.ftp_result_)); -} - -::PROTOBUF_NAMESPACE_ID::Metadata AreFilesIdenticalResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[17]); -} -// =================================================================== - -class SetRootDirectoryRequest::_Internal { - public: -}; - -SetRootDirectoryRequest::SetRootDirectoryRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.SetRootDirectoryRequest) -} -SetRootDirectoryRequest::SetRootDirectoryRequest(const SetRootDirectoryRequest& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - SetRootDirectoryRequest* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_.root_dir_) {} - - , /*decltype(_impl_._cached_size_)*/{}}; - - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - _impl_.root_dir_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.root_dir_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_root_dir().empty()) { - _this->_impl_.root_dir_.Set(from._internal_root_dir(), _this->GetArenaForAllocation()); - } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.SetRootDirectoryRequest) -} - -inline void SetRootDirectoryRequest::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_.root_dir_) {} - - , /*decltype(_impl_._cached_size_)*/{} - }; - _impl_.root_dir_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.root_dir_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING -} - -SetRootDirectoryRequest::~SetRootDirectoryRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.SetRootDirectoryRequest) - if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { - (void)arena; - return; - } - SharedDtor(); -} - -inline void SetRootDirectoryRequest::SharedDtor() { - ABSL_DCHECK(GetArenaForAllocation() == nullptr); - _impl_.root_dir_.Destroy(); -} - -void SetRootDirectoryRequest::SetCachedSize(int size) const { - _impl_._cached_size_.Set(size); -} - -void SetRootDirectoryRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.SetRootDirectoryRequest) - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - _impl_.root_dir_.ClearToEmpty(); - _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); -} - -const char* SetRootDirectoryRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { -#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - while (!ctx->Done(&ptr)) { - ::uint32_t tag; - ptr = ::_pbi::ReadTag(ptr, &tag); - switch (tag >> 3) { - // string root_dir = 1; - case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - auto str = _internal_mutable_root_dir(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); - CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.ftp.SetRootDirectoryRequest.root_dir")); - } else { - goto handle_unusual; - } - continue; - default: - goto handle_unusual; - } // switch - handle_unusual: - if ((tag == 0) || ((tag & 7) == 4)) { - CHK_(ptr); - ctx->SetLastTag(tag); - goto message_done; - } - ptr = UnknownFieldParse( - tag, - _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), - ptr, ctx); - CHK_(ptr != nullptr); - } // while -message_done: - return ptr; -failure: - ptr = nullptr; - goto message_done; -#undef CHK_ -} - -::uint8_t* SetRootDirectoryRequest::_InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.SetRootDirectoryRequest) - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - // string root_dir = 1; - if (!this->_internal_root_dir().empty()) { - const std::string& _s = this->_internal_root_dir(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.ftp.SetRootDirectoryRequest.root_dir"); - target = stream->WriteStringMaybeAliased(1, _s, target); - } - - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { - target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( - _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); - } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.SetRootDirectoryRequest) - return target; -} - -::size_t SetRootDirectoryRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.SetRootDirectoryRequest) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // string root_dir = 1; - if (!this->_internal_root_dir().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_root_dir()); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetRootDirectoryRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - SetRootDirectoryRequest::MergeImpl -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetRootDirectoryRequest::GetClassData() const { return &_class_data_; } - - -void SetRootDirectoryRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp.SetRootDirectoryRequest) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - if (!from._internal_root_dir().empty()) { - _this->_internal_set_root_dir(from._internal_root_dir()); - } - _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); -} - -void SetRootDirectoryRequest::CopyFrom(const SetRootDirectoryRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp.SetRootDirectoryRequest) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool SetRootDirectoryRequest::IsInitialized() const { - return true; -} - -void SetRootDirectoryRequest::InternalSwap(SetRootDirectoryRequest* other) { - using std::swap; - auto* lhs_arena = GetArenaForAllocation(); - auto* rhs_arena = other->GetArenaForAllocation(); - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.root_dir_, lhs_arena, - &other->_impl_.root_dir_, rhs_arena); -} - -::PROTOBUF_NAMESPACE_ID::Metadata SetRootDirectoryRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata AreFilesIdenticalRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[18]); + file_level_metadata_ftp_2fftp_2eproto[14]); } // =================================================================== -class SetRootDirectoryResponse::_Internal { +class AreFilesIdenticalResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(SetRootDirectoryResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::ftp::FtpResult& ftp_result(const SetRootDirectoryResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(AreFilesIdenticalResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::ftp::FtpResult& ftp_result(const AreFilesIdenticalResponse* msg); static void set_has_ftp_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; const ::mavsdk::rpc::ftp::FtpResult& -SetRootDirectoryResponse::_Internal::ftp_result(const SetRootDirectoryResponse* msg) { +AreFilesIdenticalResponse::_Internal::ftp_result(const AreFilesIdenticalResponse* msg) { return *msg->_impl_.ftp_result_; } -SetRootDirectoryResponse::SetRootDirectoryResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +AreFilesIdenticalResponse::AreFilesIdenticalResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.SetRootDirectoryResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.AreFilesIdenticalResponse) } -SetRootDirectoryResponse::SetRootDirectoryResponse(const SetRootDirectoryResponse& from) +AreFilesIdenticalResponse::AreFilesIdenticalResponse(const AreFilesIdenticalResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message() { - SetRootDirectoryResponse* const _this = this; (void)_this; + AreFilesIdenticalResponse* const _this = this; (void)_this; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){from._impl_._has_bits_} , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.ftp_result_){nullptr}}; + , decltype(_impl_.ftp_result_){nullptr} + , decltype(_impl_.are_identical_) {} + }; _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { _this->_impl_.ftp_result_ = new ::mavsdk::rpc::ftp::FtpResult(*from._impl_.ftp_result_); } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.SetRootDirectoryResponse) + _this->_impl_.are_identical_ = from._impl_.are_identical_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.AreFilesIdenticalResponse) } -inline void SetRootDirectoryResponse::SharedCtor(::_pb::Arena* arena) { +inline void AreFilesIdenticalResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){} , /*decltype(_impl_._cached_size_)*/{} , decltype(_impl_.ftp_result_){nullptr} + , decltype(_impl_.are_identical_) { false } + }; } -SetRootDirectoryResponse::~SetRootDirectoryResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.SetRootDirectoryResponse) +AreFilesIdenticalResponse::~AreFilesIdenticalResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.AreFilesIdenticalResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -5053,17 +4243,17 @@ SetRootDirectoryResponse::~SetRootDirectoryResponse() { SharedDtor(); } -inline void SetRootDirectoryResponse::SharedDtor() { +inline void AreFilesIdenticalResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); if (this != internal_default_instance()) delete _impl_.ftp_result_; } -void SetRootDirectoryResponse::SetCachedSize(int size) const { +void AreFilesIdenticalResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void SetRootDirectoryResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.SetRootDirectoryResponse) +void AreFilesIdenticalResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -5073,11 +4263,12 @@ void SetRootDirectoryResponse::Clear() { ABSL_DCHECK(_impl_.ftp_result_ != nullptr); _impl_.ftp_result_->Clear(); } + _impl_.are_identical_ = false; _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* SetRootDirectoryResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* AreFilesIdenticalResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { @@ -5093,6 +4284,15 @@ const char* SetRootDirectoryResponse::_InternalParse(const char* ptr, ::_pbi::Pa goto handle_unusual; } continue; + // bool are_identical = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 16)) { + _impl_.are_identical_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; default: goto handle_unusual; } // switch @@ -5117,9 +4317,9 @@ const char* SetRootDirectoryResponse::_InternalParse(const char* ptr, ::_pbi::Pa #undef CHK_ } -::uint8_t* SetRootDirectoryResponse::_InternalSerialize( +::uint8_t* AreFilesIdenticalResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.SetRootDirectoryResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -5131,16 +4331,23 @@ ::uint8_t* SetRootDirectoryResponse::_InternalSerialize( _Internal::ftp_result(this).GetCachedSize(), target, stream); } + // bool are_identical = 2; + if (this->_internal_are_identical() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 2, this->_internal_are_identical(), target); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.SetRootDirectoryResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.AreFilesIdenticalResponse) return target; } -::size_t SetRootDirectoryResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.SetRootDirectoryResponse) +::size_t AreFilesIdenticalResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -5155,20 +4362,25 @@ ::size_t SetRootDirectoryResponse::ByteSizeLong() const { *_impl_.ftp_result_); } + // bool are_identical = 2; + if (this->_internal_are_identical() != 0) { + total_size += 2; + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetRootDirectoryResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData AreFilesIdenticalResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - SetRootDirectoryResponse::MergeImpl + AreFilesIdenticalResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetRootDirectoryResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*AreFilesIdenticalResponse::GetClassData() const { return &_class_data_; } -void SetRootDirectoryResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp.SetRootDirectoryResponse) +void AreFilesIdenticalResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -5177,31 +4389,39 @@ void SetRootDirectoryResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_ms _this->_internal_mutable_ftp_result()->::mavsdk::rpc::ftp::FtpResult::MergeFrom( from._internal_ftp_result()); } + if (from._internal_are_identical() != 0) { + _this->_internal_set_are_identical(from._internal_are_identical()); + } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void SetRootDirectoryResponse::CopyFrom(const SetRootDirectoryResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp.SetRootDirectoryResponse) +void AreFilesIdenticalResponse::CopyFrom(const AreFilesIdenticalResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp.AreFilesIdenticalResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool SetRootDirectoryResponse::IsInitialized() const { +bool AreFilesIdenticalResponse::IsInitialized() const { return true; } -void SetRootDirectoryResponse::InternalSwap(SetRootDirectoryResponse* other) { +void AreFilesIdenticalResponse::InternalSwap(AreFilesIdenticalResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.ftp_result_, other->_impl_.ftp_result_); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(AreFilesIdenticalResponse, _impl_.are_identical_) + + sizeof(AreFilesIdenticalResponse::_impl_.are_identical_) + - PROTOBUF_FIELD_OFFSET(AreFilesIdenticalResponse, _impl_.ftp_result_)>( + reinterpret_cast(&_impl_.ftp_result_), + reinterpret_cast(&other->_impl_.ftp_result_)); } -::PROTOBUF_NAMESPACE_ID::Metadata SetRootDirectoryResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata AreFilesIdenticalResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[19]); + file_level_metadata_ftp_2fftp_2eproto[15]); } // =================================================================== @@ -5375,7 +4595,7 @@ void SetTargetCompidRequest::InternalSwap(SetTargetCompidRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata SetTargetCompidRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[20]); + file_level_metadata_ftp_2fftp_2eproto[16]); } // =================================================================== @@ -5580,219 +4800,7 @@ void SetTargetCompidResponse::InternalSwap(SetTargetCompidResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata SetTargetCompidResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[21]); -} -// =================================================================== - -class GetOurCompidRequest::_Internal { - public: -}; - -GetOurCompidRequest::GetOurCompidRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.GetOurCompidRequest) -} -GetOurCompidRequest::GetOurCompidRequest(const GetOurCompidRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - GetOurCompidRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.GetOurCompidRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData GetOurCompidRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetOurCompidRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata GetOurCompidRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[22]); -} -// =================================================================== - -class GetOurCompidResponse::_Internal { - public: -}; - -GetOurCompidResponse::GetOurCompidResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp.GetOurCompidResponse) -} -GetOurCompidResponse::GetOurCompidResponse(const GetOurCompidResponse& from) - : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( - from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp.GetOurCompidResponse) -} - -inline void GetOurCompidResponse::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_.compid_) { 0u } - - , /*decltype(_impl_._cached_size_)*/{} - }; -} - -GetOurCompidResponse::~GetOurCompidResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp.GetOurCompidResponse) - if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { - (void)arena; - return; - } - SharedDtor(); -} - -inline void GetOurCompidResponse::SharedDtor() { - ABSL_DCHECK(GetArenaForAllocation() == nullptr); -} - -void GetOurCompidResponse::SetCachedSize(int size) const { - _impl_._cached_size_.Set(size); -} - -void GetOurCompidResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp.GetOurCompidResponse) - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - _impl_.compid_ = 0u; - _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); -} - -const char* GetOurCompidResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { -#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - while (!ctx->Done(&ptr)) { - ::uint32_t tag; - ptr = ::_pbi::ReadTag(ptr, &tag); - switch (tag >> 3) { - // uint32 compid = 1; - case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.compid_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - } else { - goto handle_unusual; - } - continue; - default: - goto handle_unusual; - } // switch - handle_unusual: - if ((tag == 0) || ((tag & 7) == 4)) { - CHK_(ptr); - ctx->SetLastTag(tag); - goto message_done; - } - ptr = UnknownFieldParse( - tag, - _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), - ptr, ctx); - CHK_(ptr != nullptr); - } // while -message_done: - return ptr; -failure: - ptr = nullptr; - goto message_done; -#undef CHK_ -} - -::uint8_t* GetOurCompidResponse::_InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp.GetOurCompidResponse) - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - // uint32 compid = 1; - if (this->_internal_compid() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 1, this->_internal_compid(), target); - } - - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { - target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( - _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); - } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp.GetOurCompidResponse) - return target; -} - -::size_t GetOurCompidResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp.GetOurCompidResponse) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // uint32 compid = 1; - if (this->_internal_compid() != 0) { - total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( - this->_internal_compid()); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData GetOurCompidResponse::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - GetOurCompidResponse::MergeImpl -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetOurCompidResponse::GetClassData() const { return &_class_data_; } - - -void GetOurCompidResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp.GetOurCompidResponse) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - if (from._internal_compid() != 0) { - _this->_internal_set_compid(from._internal_compid()); - } - _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); -} - -void GetOurCompidResponse::CopyFrom(const GetOurCompidResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp.GetOurCompidResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool GetOurCompidResponse::IsInitialized() const { - return true; -} - -void GetOurCompidResponse::InternalSwap(GetOurCompidResponse* other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - - swap(_impl_.compid_, other->_impl_.compid_); -} - -::PROTOBUF_NAMESPACE_ID::Metadata GetOurCompidResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[23]); + file_level_metadata_ftp_2fftp_2eproto[17]); } // =================================================================== @@ -5999,7 +5007,7 @@ void ProgressData::InternalSwap(ProgressData* other) { ::PROTOBUF_NAMESPACE_ID::Metadata ProgressData::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[24]); + file_level_metadata_ftp_2fftp_2eproto[18]); } // =================================================================== @@ -6228,21 +5236,13 @@ void FtpResult::InternalSwap(FtpResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata FtpResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_ftp_2fftp_2eproto_getter, &descriptor_table_ftp_2fftp_2eproto_once, - file_level_metadata_ftp_2fftp_2eproto[25]); + file_level_metadata_ftp_2fftp_2eproto[19]); } // @@protoc_insertion_point(namespace_scope) } // namespace ftp } // namespace rpc } // namespace mavsdk PROTOBUF_NAMESPACE_OPEN -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::ResetRequest* -Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::ResetRequest >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::ResetRequest >(arena); -} -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::ResetResponse* -Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::ResetResponse >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::ResetResponse >(arena); -} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::SubscribeDownloadRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::SubscribeDownloadRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::SubscribeDownloadRequest >(arena); @@ -6307,14 +5307,6 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::AreFilesIdenticalResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::AreFilesIdenticalResponse >(arena); } -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::SetRootDirectoryRequest* -Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::SetRootDirectoryRequest >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::SetRootDirectoryRequest >(arena); -} -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::SetRootDirectoryResponse* -Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::SetRootDirectoryResponse >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::SetRootDirectoryResponse >(arena); -} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::SetTargetCompidRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::SetTargetCompidRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::SetTargetCompidRequest >(arena); @@ -6323,14 +5315,6 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::SetTargetCompidResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::SetTargetCompidResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::SetTargetCompidResponse >(arena); } -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::GetOurCompidRequest* -Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::GetOurCompidRequest >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::GetOurCompidRequest >(arena); -} -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::GetOurCompidResponse* -Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::GetOurCompidResponse >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::GetOurCompidResponse >(arena); -} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp::ProgressData* Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp::ProgressData >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp::ProgressData >(arena); diff --git a/src/mavsdk_server/src/generated/ftp/ftp.pb.h b/src/mavsdk_server/src/generated/ftp/ftp.pb.h index 81fed5e27c..0074513c2c 100644 --- a/src/mavsdk_server/src/generated/ftp/ftp.pb.h +++ b/src/mavsdk_server/src/generated/ftp/ftp.pb.h @@ -24,7 +24,6 @@ #include "google/protobuf/io/coded_stream.h" #include "google/protobuf/arena.h" #include "google/protobuf/arenastring.h" -#include "google/protobuf/generated_message_bases.h" #include "google/protobuf/generated_message_util.h" #include "google/protobuf/metadata_lite.h" #include "google/protobuf/generated_message_reflection.h" @@ -74,12 +73,6 @@ extern DownloadResponseDefaultTypeInternal _DownloadResponse_default_instance_; class FtpResult; struct FtpResultDefaultTypeInternal; extern FtpResultDefaultTypeInternal _FtpResult_default_instance_; -class GetOurCompidRequest; -struct GetOurCompidRequestDefaultTypeInternal; -extern GetOurCompidRequestDefaultTypeInternal _GetOurCompidRequest_default_instance_; -class GetOurCompidResponse; -struct GetOurCompidResponseDefaultTypeInternal; -extern GetOurCompidResponseDefaultTypeInternal _GetOurCompidResponse_default_instance_; class ListDirectoryRequest; struct ListDirectoryRequestDefaultTypeInternal; extern ListDirectoryRequestDefaultTypeInternal _ListDirectoryRequest_default_instance_; @@ -107,18 +100,6 @@ extern RenameRequestDefaultTypeInternal _RenameRequest_default_instance_; class RenameResponse; struct RenameResponseDefaultTypeInternal; extern RenameResponseDefaultTypeInternal _RenameResponse_default_instance_; -class ResetRequest; -struct ResetRequestDefaultTypeInternal; -extern ResetRequestDefaultTypeInternal _ResetRequest_default_instance_; -class ResetResponse; -struct ResetResponseDefaultTypeInternal; -extern ResetResponseDefaultTypeInternal _ResetResponse_default_instance_; -class SetRootDirectoryRequest; -struct SetRootDirectoryRequestDefaultTypeInternal; -extern SetRootDirectoryRequestDefaultTypeInternal _SetRootDirectoryRequest_default_instance_; -class SetRootDirectoryResponse; -struct SetRootDirectoryResponseDefaultTypeInternal; -extern SetRootDirectoryResponseDefaultTypeInternal _SetRootDirectoryResponse_default_instance_; class SetTargetCompidRequest; struct SetTargetCompidRequestDefaultTypeInternal; extern SetTargetCompidRequestDefaultTypeInternal _SetTargetCompidRequest_default_instance_; @@ -151,10 +132,6 @@ ::mavsdk::rpc::ftp::DownloadResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::f template <> ::mavsdk::rpc::ftp::FtpResult* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::FtpResult>(Arena*); template <> -::mavsdk::rpc::ftp::GetOurCompidRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::GetOurCompidRequest>(Arena*); -template <> -::mavsdk::rpc::ftp::GetOurCompidResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::GetOurCompidResponse>(Arena*); -template <> ::mavsdk::rpc::ftp::ListDirectoryRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::ListDirectoryRequest>(Arena*); template <> ::mavsdk::rpc::ftp::ListDirectoryResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::ListDirectoryResponse>(Arena*); @@ -173,14 +150,6 @@ ::mavsdk::rpc::ftp::RenameRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp: template <> ::mavsdk::rpc::ftp::RenameResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::RenameResponse>(Arena*); template <> -::mavsdk::rpc::ftp::ResetRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::ResetRequest>(Arena*); -template <> -::mavsdk::rpc::ftp::ResetResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::ResetResponse>(Arena*); -template <> -::mavsdk::rpc::ftp::SetRootDirectoryRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::SetRootDirectoryRequest>(Arena*); -template <> -::mavsdk::rpc::ftp::SetRootDirectoryResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::SetRootDirectoryResponse>(Arena*); -template <> ::mavsdk::rpc::ftp::SetTargetCompidRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::SetTargetCompidRequest>(Arena*); template <> ::mavsdk::rpc::ftp::SetTargetCompidResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp::SetTargetCompidResponse>(Arena*); @@ -244,290 +213,6 @@ inline bool FtpResult_Result_Parse(absl::string_view name, FtpResult_Result* val // ------------------------------------------------------------------- -class ResetRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.ResetRequest) */ { - public: - inline ResetRequest() : ResetRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR ResetRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - ResetRequest(const ResetRequest& from); - ResetRequest(ResetRequest&& from) noexcept - : ResetRequest() { - *this = ::std::move(from); - } - - inline ResetRequest& operator=(const ResetRequest& from) { - CopyFrom(from); - return *this; - } - inline ResetRequest& operator=(ResetRequest&& from) noexcept { - if (this == &from) return *this; - if (GetOwningArena() == from.GetOwningArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetOwningArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { - return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); - } - inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { - return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); - } - - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const ResetRequest& default_instance() { - return *internal_default_instance(); - } - static inline const ResetRequest* internal_default_instance() { - return reinterpret_cast( - &_ResetRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 0; - - friend void swap(ResetRequest& a, ResetRequest& b) { - a.Swap(&b); - } - inline void Swap(ResetRequest* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() != nullptr && - GetOwningArena() == other->GetOwningArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() == other->GetOwningArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(ResetRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - ResetRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const ResetRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const ResetRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); - } - public: - - private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.ResetRequest"; - } - protected: - explicit ResetRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); - public: - - static const ClassData _class_data_; - const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - - ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.ResetRequest) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - }; - friend struct ::TableStruct_ftp_2fftp_2eproto; -};// ------------------------------------------------------------------- - -class ResetResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.ResetResponse) */ { - public: - inline ResetResponse() : ResetResponse(nullptr) {} - ~ResetResponse() override; - template - explicit PROTOBUF_CONSTEXPR ResetResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - ResetResponse(const ResetResponse& from); - ResetResponse(ResetResponse&& from) noexcept - : ResetResponse() { - *this = ::std::move(from); - } - - inline ResetResponse& operator=(const ResetResponse& from) { - CopyFrom(from); - return *this; - } - inline ResetResponse& operator=(ResetResponse&& from) noexcept { - if (this == &from) return *this; - if (GetOwningArena() == from.GetOwningArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetOwningArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { - return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); - } - inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { - return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); - } - - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const ResetResponse& default_instance() { - return *internal_default_instance(); - } - static inline const ResetResponse* internal_default_instance() { - return reinterpret_cast( - &_ResetResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 1; - - friend void swap(ResetResponse& a, ResetResponse& b) { - a.Swap(&b); - } - inline void Swap(ResetResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() != nullptr && - GetOwningArena() == other->GetOwningArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() == other->GetOwningArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(ResetResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - ResetResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const ResetResponse& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const ResetResponse& from) { - ResetResponse::MergeImpl(*this, from); - } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); - public: - PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; - bool IsInitialized() const final; - - ::size_t ByteSizeLong() const final; - const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(ResetResponse* other); - - private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.ResetResponse"; - } - protected: - explicit ResetResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); - public: - - static const ClassData _class_data_; - const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - - ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - enum : int { - kFtpResultFieldNumber = 1, - }; - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - bool has_ftp_result() const; - void clear_ftp_result() ; - const ::mavsdk::rpc::ftp::FtpResult& ftp_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::ftp::FtpResult* release_ftp_result(); - ::mavsdk::rpc::ftp::FtpResult* mutable_ftp_result(); - void set_allocated_ftp_result(::mavsdk::rpc::ftp::FtpResult* ftp_result); - private: - const ::mavsdk::rpc::ftp::FtpResult& _internal_ftp_result() const; - ::mavsdk::rpc::ftp::FtpResult* _internal_mutable_ftp_result(); - public: - void unsafe_arena_set_allocated_ftp_result( - ::mavsdk::rpc::ftp::FtpResult* ftp_result); - ::mavsdk::rpc::ftp::FtpResult* unsafe_arena_release_ftp_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.ResetResponse) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::ftp::FtpResult* ftp_result_; - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_ftp_2fftp_2eproto; -};// ------------------------------------------------------------------- - class SubscribeDownloadRequest final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.SubscribeDownloadRequest) */ { public: @@ -584,7 +269,7 @@ class SubscribeDownloadRequest final : &_SubscribeDownloadRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 2; + 0; friend void swap(SubscribeDownloadRequest& a, SubscribeDownloadRequest& b) { a.Swap(&b); @@ -658,6 +343,7 @@ class SubscribeDownloadRequest final : enum : int { kRemoteFilePathFieldNumber = 1, kLocalDirFieldNumber = 2, + kUseBurstFieldNumber = 3, }; // string remote_file_path = 1; void clear_remote_file_path() ; @@ -698,6 +384,16 @@ class SubscribeDownloadRequest final : const std::string& value); std::string* _internal_mutable_local_dir(); + public: + // bool use_burst = 3; + void clear_use_burst() ; + bool use_burst() const; + void set_use_burst(bool value); + + private: + bool _internal_use_burst() const; + void _internal_set_use_burst(bool value); + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SubscribeDownloadRequest) private: @@ -709,6 +405,7 @@ class SubscribeDownloadRequest final : struct Impl_ { ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr remote_file_path_; ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr local_dir_; + bool use_burst_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; @@ -771,7 +468,7 @@ class DownloadResponse final : &_DownloadResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 3; + 1; friend void swap(DownloadResponse& a, DownloadResponse& b) { a.Swap(&b); @@ -947,7 +644,7 @@ class SubscribeUploadRequest final : &_SubscribeUploadRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 4; + 2; friend void swap(SubscribeUploadRequest& a, SubscribeUploadRequest& b) { a.Swap(&b); @@ -1134,7 +831,7 @@ class UploadResponse final : &_UploadResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 5; + 3; friend void swap(UploadResponse& a, UploadResponse& b) { a.Swap(&b); @@ -1310,7 +1007,7 @@ class ListDirectoryRequest final : &_ListDirectoryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 4; friend void swap(ListDirectoryRequest& a, ListDirectoryRequest& b) { a.Swap(&b); @@ -1475,7 +1172,7 @@ class ListDirectoryResponse final : &_ListDirectoryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 7; + 5; friend void swap(ListDirectoryResponse& a, ListDirectoryResponse& b) { a.Swap(&b); @@ -1667,7 +1364,7 @@ class CreateDirectoryRequest final : &_CreateDirectoryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 6; friend void swap(CreateDirectoryRequest& a, CreateDirectoryRequest& b) { a.Swap(&b); @@ -1832,7 +1529,7 @@ class CreateDirectoryResponse final : &_CreateDirectoryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 9; + 7; friend void swap(CreateDirectoryResponse& a, CreateDirectoryResponse& b) { a.Swap(&b); @@ -1992,7 +1689,7 @@ class RemoveDirectoryRequest final : &_RemoveDirectoryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 8; friend void swap(RemoveDirectoryRequest& a, RemoveDirectoryRequest& b) { a.Swap(&b); @@ -2157,7 +1854,7 @@ class RemoveDirectoryResponse final : &_RemoveDirectoryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 9; friend void swap(RemoveDirectoryResponse& a, RemoveDirectoryResponse& b) { a.Swap(&b); @@ -2317,7 +2014,7 @@ class RemoveFileRequest final : &_RemoveFileRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 10; friend void swap(RemoveFileRequest& a, RemoveFileRequest& b) { a.Swap(&b); @@ -2482,7 +2179,7 @@ class RemoveFileResponse final : &_RemoveFileResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 11; friend void swap(RemoveFileResponse& a, RemoveFileResponse& b) { a.Swap(&b); @@ -2642,7 +2339,7 @@ class RenameRequest final : &_RenameRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 12; friend void swap(RenameRequest& a, RenameRequest& b) { a.Swap(&b); @@ -2829,7 +2526,7 @@ class RenameResponse final : &_RenameResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 13; friend void swap(RenameResponse& a, RenameResponse& b) { a.Swap(&b); @@ -2989,7 +2686,7 @@ class AreFilesIdenticalRequest final : &_AreFilesIdenticalRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 14; friend void swap(AreFilesIdenticalRequest& a, AreFilesIdenticalRequest& b) { a.Swap(&b); @@ -3176,7 +2873,7 @@ class AreFilesIdenticalResponse final : &_AreFilesIdenticalResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 15; friend void swap(AreFilesIdenticalResponse& a, AreFilesIdenticalResponse& b) { a.Swap(&b); @@ -3292,25 +2989,25 @@ class AreFilesIdenticalResponse final : friend struct ::TableStruct_ftp_2fftp_2eproto; };// ------------------------------------------------------------------- -class SetRootDirectoryRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.SetRootDirectoryRequest) */ { +class SetTargetCompidRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.SetTargetCompidRequest) */ { public: - inline SetRootDirectoryRequest() : SetRootDirectoryRequest(nullptr) {} - ~SetRootDirectoryRequest() override; + inline SetTargetCompidRequest() : SetTargetCompidRequest(nullptr) {} + ~SetTargetCompidRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRootDirectoryRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetTargetCompidRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SetRootDirectoryRequest(const SetRootDirectoryRequest& from); - SetRootDirectoryRequest(SetRootDirectoryRequest&& from) noexcept - : SetRootDirectoryRequest() { + SetTargetCompidRequest(const SetTargetCompidRequest& from); + SetTargetCompidRequest(SetTargetCompidRequest&& from) noexcept + : SetTargetCompidRequest() { *this = ::std::move(from); } - inline SetRootDirectoryRequest& operator=(const SetRootDirectoryRequest& from) { + inline SetTargetCompidRequest& operator=(const SetTargetCompidRequest& from) { CopyFrom(from); return *this; } - inline SetRootDirectoryRequest& operator=(SetRootDirectoryRequest&& from) noexcept { + inline SetTargetCompidRequest& operator=(SetTargetCompidRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3340,20 +3037,20 @@ class SetRootDirectoryRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRootDirectoryRequest& default_instance() { + static const SetTargetCompidRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRootDirectoryRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRootDirectoryRequest_default_instance_); + static inline const SetTargetCompidRequest* internal_default_instance() { + return reinterpret_cast( + &_SetTargetCompidRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 16; - friend void swap(SetRootDirectoryRequest& a, SetRootDirectoryRequest& b) { + friend void swap(SetTargetCompidRequest& a, SetTargetCompidRequest& b) { a.Swap(&b); } - inline void Swap(SetRootDirectoryRequest* other) { + inline void Swap(SetTargetCompidRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3366,7 +3063,7 @@ class SetRootDirectoryRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRootDirectoryRequest* other) { + void UnsafeArenaSwap(SetTargetCompidRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3374,14 +3071,14 @@ class SetRootDirectoryRequest final : // implements Message ---------------------------------------------- - SetRootDirectoryRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetTargetCompidRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const SetRootDirectoryRequest& from); + void CopyFrom(const SetTargetCompidRequest& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const SetRootDirectoryRequest& from) { - SetRootDirectoryRequest::MergeImpl(*this, from); + void MergeFrom( const SetTargetCompidRequest& from) { + SetTargetCompidRequest::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3399,15 +3096,15 @@ class SetRootDirectoryRequest final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(SetRootDirectoryRequest* other); + void InternalSwap(SetTargetCompidRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.SetRootDirectoryRequest"; + return "mavsdk.rpc.ftp.SetTargetCompidRequest"; } protected: - explicit SetRootDirectoryRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SetTargetCompidRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3420,188 +3117,19 @@ class SetRootDirectoryRequest final : // accessors ------------------------------------------------------- enum : int { - kRootDirFieldNumber = 1, - }; - // string root_dir = 1; - void clear_root_dir() ; - const std::string& root_dir() const; - - - - - template - void set_root_dir(Arg_&& arg, Args_... args); - std::string* mutable_root_dir(); - PROTOBUF_NODISCARD std::string* release_root_dir(); - void set_allocated_root_dir(std::string* ptr); - - private: - const std::string& _internal_root_dir() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_root_dir( - const std::string& value); - std::string* _internal_mutable_root_dir(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetRootDirectoryRequest) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr root_dir_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + kCompidFieldNumber = 1, }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_ftp_2fftp_2eproto; -};// ------------------------------------------------------------------- - -class SetRootDirectoryResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.SetRootDirectoryResponse) */ { - public: - inline SetRootDirectoryResponse() : SetRootDirectoryResponse(nullptr) {} - ~SetRootDirectoryResponse() override; - template - explicit PROTOBUF_CONSTEXPR SetRootDirectoryResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - SetRootDirectoryResponse(const SetRootDirectoryResponse& from); - SetRootDirectoryResponse(SetRootDirectoryResponse&& from) noexcept - : SetRootDirectoryResponse() { - *this = ::std::move(from); - } - - inline SetRootDirectoryResponse& operator=(const SetRootDirectoryResponse& from) { - CopyFrom(from); - return *this; - } - inline SetRootDirectoryResponse& operator=(SetRootDirectoryResponse&& from) noexcept { - if (this == &from) return *this; - if (GetOwningArena() == from.GetOwningArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetOwningArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { - return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); - } - inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { - return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); - } - - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const SetRootDirectoryResponse& default_instance() { - return *internal_default_instance(); - } - static inline const SetRootDirectoryResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRootDirectoryResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 19; - - friend void swap(SetRootDirectoryResponse& a, SetRootDirectoryResponse& b) { - a.Swap(&b); - } - inline void Swap(SetRootDirectoryResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() != nullptr && - GetOwningArena() == other->GetOwningArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() == other->GetOwningArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(SetRootDirectoryResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - SetRootDirectoryResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const SetRootDirectoryResponse& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const SetRootDirectoryResponse& from) { - SetRootDirectoryResponse::MergeImpl(*this, from); - } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); - public: - PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; - bool IsInitialized() const final; - - ::size_t ByteSizeLong() const final; - const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(SetRootDirectoryResponse* other); + // uint32 compid = 1; + void clear_compid() ; + ::uint32_t compid() const; + void set_compid(::uint32_t value); private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.SetRootDirectoryResponse"; - } - protected: - explicit SetRootDirectoryResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); - public: - - static const ClassData _class_data_; - const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - - ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- + ::uint32_t _internal_compid() const; + void _internal_set_compid(::uint32_t value); - enum : int { - kFtpResultFieldNumber = 1, - }; - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - bool has_ftp_result() const; - void clear_ftp_result() ; - const ::mavsdk::rpc::ftp::FtpResult& ftp_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::ftp::FtpResult* release_ftp_result(); - ::mavsdk::rpc::ftp::FtpResult* mutable_ftp_result(); - void set_allocated_ftp_result(::mavsdk::rpc::ftp::FtpResult* ftp_result); - private: - const ::mavsdk::rpc::ftp::FtpResult& _internal_ftp_result() const; - ::mavsdk::rpc::ftp::FtpResult* _internal_mutable_ftp_result(); public: - void unsafe_arena_set_allocated_ftp_result( - ::mavsdk::rpc::ftp::FtpResult* ftp_result); - ::mavsdk::rpc::ftp::FtpResult* unsafe_arena_release_ftp_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetRootDirectoryResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetCompidRequest) private: class _Internal; @@ -3609,163 +3137,7 @@ class SetRootDirectoryResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::ftp::FtpResult* ftp_result_; - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_ftp_2fftp_2eproto; -};// ------------------------------------------------------------------- - -class SetTargetCompidRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.SetTargetCompidRequest) */ { - public: - inline SetTargetCompidRequest() : SetTargetCompidRequest(nullptr) {} - ~SetTargetCompidRequest() override; - template - explicit PROTOBUF_CONSTEXPR SetTargetCompidRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - SetTargetCompidRequest(const SetTargetCompidRequest& from); - SetTargetCompidRequest(SetTargetCompidRequest&& from) noexcept - : SetTargetCompidRequest() { - *this = ::std::move(from); - } - - inline SetTargetCompidRequest& operator=(const SetTargetCompidRequest& from) { - CopyFrom(from); - return *this; - } - inline SetTargetCompidRequest& operator=(SetTargetCompidRequest&& from) noexcept { - if (this == &from) return *this; - if (GetOwningArena() == from.GetOwningArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetOwningArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { - return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); - } - inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { - return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); - } - - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const SetTargetCompidRequest& default_instance() { - return *internal_default_instance(); - } - static inline const SetTargetCompidRequest* internal_default_instance() { - return reinterpret_cast( - &_SetTargetCompidRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 20; - - friend void swap(SetTargetCompidRequest& a, SetTargetCompidRequest& b) { - a.Swap(&b); - } - inline void Swap(SetTargetCompidRequest* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() != nullptr && - GetOwningArena() == other->GetOwningArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() == other->GetOwningArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(SetTargetCompidRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - SetTargetCompidRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const SetTargetCompidRequest& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const SetTargetCompidRequest& from) { - SetTargetCompidRequest::MergeImpl(*this, from); - } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); - public: - PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; - bool IsInitialized() const final; - - ::size_t ByteSizeLong() const final; - const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(SetTargetCompidRequest* other); - - private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.SetTargetCompidRequest"; - } - protected: - explicit SetTargetCompidRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); - public: - - static const ClassData _class_data_; - const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - - ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - enum : int { - kCompidFieldNumber = 1, - }; - // uint32 compid = 1; - void clear_compid() ; - ::uint32_t compid() const; - void set_compid(::uint32_t value); - - private: - ::uint32_t _internal_compid() const; - void _internal_set_compid(::uint32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetCompidRequest) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::uint32_t compid_; + ::uint32_t compid_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; @@ -3773,308 +3145,24 @@ class SetTargetCompidRequest final : };// ------------------------------------------------------------------- class SetTargetCompidResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.SetTargetCompidResponse) */ { - public: - inline SetTargetCompidResponse() : SetTargetCompidResponse(nullptr) {} - ~SetTargetCompidResponse() override; - template - explicit PROTOBUF_CONSTEXPR SetTargetCompidResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - SetTargetCompidResponse(const SetTargetCompidResponse& from); - SetTargetCompidResponse(SetTargetCompidResponse&& from) noexcept - : SetTargetCompidResponse() { - *this = ::std::move(from); - } - - inline SetTargetCompidResponse& operator=(const SetTargetCompidResponse& from) { - CopyFrom(from); - return *this; - } - inline SetTargetCompidResponse& operator=(SetTargetCompidResponse&& from) noexcept { - if (this == &from) return *this; - if (GetOwningArena() == from.GetOwningArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetOwningArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { - return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); - } - inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { - return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); - } - - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const SetTargetCompidResponse& default_instance() { - return *internal_default_instance(); - } - static inline const SetTargetCompidResponse* internal_default_instance() { - return reinterpret_cast( - &_SetTargetCompidResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 21; - - friend void swap(SetTargetCompidResponse& a, SetTargetCompidResponse& b) { - a.Swap(&b); - } - inline void Swap(SetTargetCompidResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() != nullptr && - GetOwningArena() == other->GetOwningArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() == other->GetOwningArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(SetTargetCompidResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - SetTargetCompidResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const SetTargetCompidResponse& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const SetTargetCompidResponse& from) { - SetTargetCompidResponse::MergeImpl(*this, from); - } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); - public: - PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; - bool IsInitialized() const final; - - ::size_t ByteSizeLong() const final; - const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(SetTargetCompidResponse* other); - - private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.SetTargetCompidResponse"; - } - protected: - explicit SetTargetCompidResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); - public: - - static const ClassData _class_data_; - const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - - ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - enum : int { - kFtpResultFieldNumber = 1, - }; - // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; - bool has_ftp_result() const; - void clear_ftp_result() ; - const ::mavsdk::rpc::ftp::FtpResult& ftp_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::ftp::FtpResult* release_ftp_result(); - ::mavsdk::rpc::ftp::FtpResult* mutable_ftp_result(); - void set_allocated_ftp_result(::mavsdk::rpc::ftp::FtpResult* ftp_result); - private: - const ::mavsdk::rpc::ftp::FtpResult& _internal_ftp_result() const; - ::mavsdk::rpc::ftp::FtpResult* _internal_mutable_ftp_result(); - public: - void unsafe_arena_set_allocated_ftp_result( - ::mavsdk::rpc::ftp::FtpResult* ftp_result); - ::mavsdk::rpc::ftp::FtpResult* unsafe_arena_release_ftp_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetCompidResponse) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::ftp::FtpResult* ftp_result_; - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_ftp_2fftp_2eproto; -};// ------------------------------------------------------------------- - -class GetOurCompidRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.GetOurCompidRequest) */ { - public: - inline GetOurCompidRequest() : GetOurCompidRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR GetOurCompidRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - GetOurCompidRequest(const GetOurCompidRequest& from); - GetOurCompidRequest(GetOurCompidRequest&& from) noexcept - : GetOurCompidRequest() { - *this = ::std::move(from); - } - - inline GetOurCompidRequest& operator=(const GetOurCompidRequest& from) { - CopyFrom(from); - return *this; - } - inline GetOurCompidRequest& operator=(GetOurCompidRequest&& from) noexcept { - if (this == &from) return *this; - if (GetOwningArena() == from.GetOwningArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetOwningArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { - return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); - } - inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { - return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); - } - - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const GetOurCompidRequest& default_instance() { - return *internal_default_instance(); - } - static inline const GetOurCompidRequest* internal_default_instance() { - return reinterpret_cast( - &_GetOurCompidRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 22; - - friend void swap(GetOurCompidRequest& a, GetOurCompidRequest& b) { - a.Swap(&b); - } - inline void Swap(GetOurCompidRequest* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() != nullptr && - GetOwningArena() == other->GetOwningArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetOwningArena() == other->GetOwningArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(GetOurCompidRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - GetOurCompidRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const GetOurCompidRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const GetOurCompidRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); - } - public: - - private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.GetOurCompidRequest"; - } - protected: - explicit GetOurCompidRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); - public: - - static const ClassData _class_data_; - const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - - ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.GetOurCompidRequest) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - }; - friend struct ::TableStruct_ftp_2fftp_2eproto; -};// ------------------------------------------------------------------- - -class GetOurCompidResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.GetOurCompidResponse) */ { + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp.SetTargetCompidResponse) */ { public: - inline GetOurCompidResponse() : GetOurCompidResponse(nullptr) {} - ~GetOurCompidResponse() override; + inline SetTargetCompidResponse() : SetTargetCompidResponse(nullptr) {} + ~SetTargetCompidResponse() override; template - explicit PROTOBUF_CONSTEXPR GetOurCompidResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetTargetCompidResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - GetOurCompidResponse(const GetOurCompidResponse& from); - GetOurCompidResponse(GetOurCompidResponse&& from) noexcept - : GetOurCompidResponse() { + SetTargetCompidResponse(const SetTargetCompidResponse& from); + SetTargetCompidResponse(SetTargetCompidResponse&& from) noexcept + : SetTargetCompidResponse() { *this = ::std::move(from); } - inline GetOurCompidResponse& operator=(const GetOurCompidResponse& from) { + inline SetTargetCompidResponse& operator=(const SetTargetCompidResponse& from) { CopyFrom(from); return *this; } - inline GetOurCompidResponse& operator=(GetOurCompidResponse&& from) noexcept { + inline SetTargetCompidResponse& operator=(SetTargetCompidResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4104,20 +3192,20 @@ class GetOurCompidResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GetOurCompidResponse& default_instance() { + static const SetTargetCompidResponse& default_instance() { return *internal_default_instance(); } - static inline const GetOurCompidResponse* internal_default_instance() { - return reinterpret_cast( - &_GetOurCompidResponse_default_instance_); + static inline const SetTargetCompidResponse* internal_default_instance() { + return reinterpret_cast( + &_SetTargetCompidResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 23; + 17; - friend void swap(GetOurCompidResponse& a, GetOurCompidResponse& b) { + friend void swap(SetTargetCompidResponse& a, SetTargetCompidResponse& b) { a.Swap(&b); } - inline void Swap(GetOurCompidResponse* other) { + inline void Swap(SetTargetCompidResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4130,7 +3218,7 @@ class GetOurCompidResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GetOurCompidResponse* other) { + void UnsafeArenaSwap(SetTargetCompidResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4138,14 +3226,14 @@ class GetOurCompidResponse final : // implements Message ---------------------------------------------- - GetOurCompidResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetTargetCompidResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const GetOurCompidResponse& from); + void CopyFrom(const SetTargetCompidResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const GetOurCompidResponse& from) { - GetOurCompidResponse::MergeImpl(*this, from); + void MergeFrom( const SetTargetCompidResponse& from) { + SetTargetCompidResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -4163,15 +3251,15 @@ class GetOurCompidResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(GetOurCompidResponse* other); + void InternalSwap(SetTargetCompidResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.ftp.GetOurCompidResponse"; + return "mavsdk.rpc.ftp.SetTargetCompidResponse"; } protected: - explicit GetOurCompidResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SetTargetCompidResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4184,19 +3272,23 @@ class GetOurCompidResponse final : // accessors ------------------------------------------------------- enum : int { - kCompidFieldNumber = 1, + kFtpResultFieldNumber = 1, }; - // uint32 compid = 1; - void clear_compid() ; - ::uint32_t compid() const; - void set_compid(::uint32_t value); - + // .mavsdk.rpc.ftp.FtpResult ftp_result = 1; + bool has_ftp_result() const; + void clear_ftp_result() ; + const ::mavsdk::rpc::ftp::FtpResult& ftp_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::ftp::FtpResult* release_ftp_result(); + ::mavsdk::rpc::ftp::FtpResult* mutable_ftp_result(); + void set_allocated_ftp_result(::mavsdk::rpc::ftp::FtpResult* ftp_result); private: - ::uint32_t _internal_compid() const; - void _internal_set_compid(::uint32_t value); - + const ::mavsdk::rpc::ftp::FtpResult& _internal_ftp_result() const; + ::mavsdk::rpc::ftp::FtpResult* _internal_mutable_ftp_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.GetOurCompidResponse) + void unsafe_arena_set_allocated_ftp_result( + ::mavsdk::rpc::ftp::FtpResult* ftp_result); + ::mavsdk::rpc::ftp::FtpResult* unsafe_arena_release_ftp_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetCompidResponse) private: class _Internal; @@ -4204,8 +3296,9 @@ class GetOurCompidResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::uint32_t compid_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::ftp::FtpResult* ftp_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_ftp_2fftp_2eproto; @@ -4267,7 +3360,7 @@ class ProgressData final : &_ProgressData_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 18; friend void swap(ProgressData& a, ProgressData& b) { a.Swap(&b); @@ -4434,7 +3527,7 @@ class FtpResult final : &_FtpResult_default_instance_); } static constexpr int kIndexInFileMessages = - 25; + 19; friend void swap(FtpResult& a, FtpResult& b) { a.Swap(&b); @@ -4600,101 +3693,6 @@ class FtpResult final : #endif // __GNUC__ // ------------------------------------------------------------------- -// ResetRequest - -// ------------------------------------------------------------------- - -// ResetResponse - -// .mavsdk.rpc.ftp.FtpResult ftp_result = 1; -inline bool ResetResponse::has_ftp_result() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.ftp_result_ != nullptr); - return value; -} -inline void ResetResponse::clear_ftp_result() { - if (_impl_.ftp_result_ != nullptr) _impl_.ftp_result_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::ftp::FtpResult& ResetResponse::_internal_ftp_result() const { - const ::mavsdk::rpc::ftp::FtpResult* p = _impl_.ftp_result_; - return p != nullptr ? *p : reinterpret_cast( - ::mavsdk::rpc::ftp::_FtpResult_default_instance_); -} -inline const ::mavsdk::rpc::ftp::FtpResult& ResetResponse::ftp_result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp.ResetResponse.ftp_result) - return _internal_ftp_result(); -} -inline void ResetResponse::unsafe_arena_set_allocated_ftp_result( - ::mavsdk::rpc::ftp::FtpResult* ftp_result) { - if (GetArenaForAllocation() == nullptr) { - delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.ftp_result_); - } - _impl_.ftp_result_ = ftp_result; - if (ftp_result) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.ftp.ResetResponse.ftp_result) -} -inline ::mavsdk::rpc::ftp::FtpResult* ResetResponse::release_ftp_result() { - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::ftp::FtpResult* temp = _impl_.ftp_result_; - _impl_.ftp_result_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); - temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); - if (GetArenaForAllocation() == nullptr) { delete old; } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArenaForAllocation() != nullptr) { - temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return temp; -} -inline ::mavsdk::rpc::ftp::FtpResult* ResetResponse::unsafe_arena_release_ftp_result() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.ftp.ResetResponse.ftp_result) - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::ftp::FtpResult* temp = _impl_.ftp_result_; - _impl_.ftp_result_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::ftp::FtpResult* ResetResponse::_internal_mutable_ftp_result() { - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.ftp_result_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::ftp::FtpResult>(GetArenaForAllocation()); - _impl_.ftp_result_ = p; - } - return _impl_.ftp_result_; -} -inline ::mavsdk::rpc::ftp::FtpResult* ResetResponse::mutable_ftp_result() { - ::mavsdk::rpc::ftp::FtpResult* _msg = _internal_mutable_ftp_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.ftp.ResetResponse.ftp_result) - return _msg; -} -inline void ResetResponse::set_allocated_ftp_result(::mavsdk::rpc::ftp::FtpResult* ftp_result) { - ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); - if (message_arena == nullptr) { - delete _impl_.ftp_result_; - } - if (ftp_result) { - ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = - ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(ftp_result); - if (message_arena != submessage_arena) { - ftp_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( - message_arena, ftp_result, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - _impl_.ftp_result_ = ftp_result; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.ftp.ResetResponse.ftp_result) -} - -// ------------------------------------------------------------------- - // SubscribeDownloadRequest // string remote_file_path = 1; @@ -4791,6 +3789,26 @@ inline void SubscribeDownloadRequest::set_allocated_local_dir(std::string* value // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.ftp.SubscribeDownloadRequest.local_dir) } +// bool use_burst = 3; +inline void SubscribeDownloadRequest::clear_use_burst() { + _impl_.use_burst_ = false; +} +inline bool SubscribeDownloadRequest::use_burst() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp.SubscribeDownloadRequest.use_burst) + return _internal_use_burst(); +} +inline void SubscribeDownloadRequest::set_use_burst(bool value) { + _internal_set_use_burst(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.ftp.SubscribeDownloadRequest.use_burst) +} +inline bool SubscribeDownloadRequest::_internal_use_burst() const { + return _impl_.use_burst_; +} +inline void SubscribeDownloadRequest::_internal_set_use_burst(bool value) { + ; + _impl_.use_burst_ = value; +} + // ------------------------------------------------------------------- // DownloadResponse @@ -6306,148 +5324,6 @@ inline void AreFilesIdenticalResponse::_internal_set_are_identical(bool value) { // ------------------------------------------------------------------- -// SetRootDirectoryRequest - -// string root_dir = 1; -inline void SetRootDirectoryRequest::clear_root_dir() { - _impl_.root_dir_.ClearToEmpty(); -} -inline const std::string& SetRootDirectoryRequest::root_dir() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp.SetRootDirectoryRequest.root_dir) - return _internal_root_dir(); -} -template -inline PROTOBUF_ALWAYS_INLINE void SetRootDirectoryRequest::set_root_dir(Arg_&& arg, - Args_... args) { - ; - _impl_.root_dir_.Set(static_cast(arg), args..., GetArenaForAllocation()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.ftp.SetRootDirectoryRequest.root_dir) -} -inline std::string* SetRootDirectoryRequest::mutable_root_dir() { - std::string* _s = _internal_mutable_root_dir(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.ftp.SetRootDirectoryRequest.root_dir) - return _s; -} -inline const std::string& SetRootDirectoryRequest::_internal_root_dir() const { - return _impl_.root_dir_.Get(); -} -inline void SetRootDirectoryRequest::_internal_set_root_dir(const std::string& value) { - ; - - - _impl_.root_dir_.Set(value, GetArenaForAllocation()); -} -inline std::string* SetRootDirectoryRequest::_internal_mutable_root_dir() { - ; - return _impl_.root_dir_.Mutable( GetArenaForAllocation()); -} -inline std::string* SetRootDirectoryRequest::release_root_dir() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.ftp.SetRootDirectoryRequest.root_dir) - return _impl_.root_dir_.Release(); -} -inline void SetRootDirectoryRequest::set_allocated_root_dir(std::string* value) { - _impl_.root_dir_.SetAllocated(value, GetArenaForAllocation()); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.root_dir_.IsDefault()) { - _impl_.root_dir_.Set("", GetArenaForAllocation()); - } - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.ftp.SetRootDirectoryRequest.root_dir) -} - -// ------------------------------------------------------------------- - -// SetRootDirectoryResponse - -// .mavsdk.rpc.ftp.FtpResult ftp_result = 1; -inline bool SetRootDirectoryResponse::has_ftp_result() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.ftp_result_ != nullptr); - return value; -} -inline void SetRootDirectoryResponse::clear_ftp_result() { - if (_impl_.ftp_result_ != nullptr) _impl_.ftp_result_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::ftp::FtpResult& SetRootDirectoryResponse::_internal_ftp_result() const { - const ::mavsdk::rpc::ftp::FtpResult* p = _impl_.ftp_result_; - return p != nullptr ? *p : reinterpret_cast( - ::mavsdk::rpc::ftp::_FtpResult_default_instance_); -} -inline const ::mavsdk::rpc::ftp::FtpResult& SetRootDirectoryResponse::ftp_result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp.SetRootDirectoryResponse.ftp_result) - return _internal_ftp_result(); -} -inline void SetRootDirectoryResponse::unsafe_arena_set_allocated_ftp_result( - ::mavsdk::rpc::ftp::FtpResult* ftp_result) { - if (GetArenaForAllocation() == nullptr) { - delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.ftp_result_); - } - _impl_.ftp_result_ = ftp_result; - if (ftp_result) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.ftp.SetRootDirectoryResponse.ftp_result) -} -inline ::mavsdk::rpc::ftp::FtpResult* SetRootDirectoryResponse::release_ftp_result() { - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::ftp::FtpResult* temp = _impl_.ftp_result_; - _impl_.ftp_result_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); - temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); - if (GetArenaForAllocation() == nullptr) { delete old; } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArenaForAllocation() != nullptr) { - temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return temp; -} -inline ::mavsdk::rpc::ftp::FtpResult* SetRootDirectoryResponse::unsafe_arena_release_ftp_result() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.ftp.SetRootDirectoryResponse.ftp_result) - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::ftp::FtpResult* temp = _impl_.ftp_result_; - _impl_.ftp_result_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::ftp::FtpResult* SetRootDirectoryResponse::_internal_mutable_ftp_result() { - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.ftp_result_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::ftp::FtpResult>(GetArenaForAllocation()); - _impl_.ftp_result_ = p; - } - return _impl_.ftp_result_; -} -inline ::mavsdk::rpc::ftp::FtpResult* SetRootDirectoryResponse::mutable_ftp_result() { - ::mavsdk::rpc::ftp::FtpResult* _msg = _internal_mutable_ftp_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.ftp.SetRootDirectoryResponse.ftp_result) - return _msg; -} -inline void SetRootDirectoryResponse::set_allocated_ftp_result(::mavsdk::rpc::ftp::FtpResult* ftp_result) { - ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); - if (message_arena == nullptr) { - delete _impl_.ftp_result_; - } - if (ftp_result) { - ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = - ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(ftp_result); - if (message_arena != submessage_arena) { - ftp_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( - message_arena, ftp_result, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - _impl_.ftp_result_ = ftp_result; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.ftp.SetRootDirectoryResponse.ftp_result) -} - -// ------------------------------------------------------------------- - // SetTargetCompidRequest // uint32 compid = 1; @@ -6563,34 +5439,6 @@ inline void SetTargetCompidResponse::set_allocated_ftp_result(::mavsdk::rpc::ftp // ------------------------------------------------------------------- -// GetOurCompidRequest - -// ------------------------------------------------------------------- - -// GetOurCompidResponse - -// uint32 compid = 1; -inline void GetOurCompidResponse::clear_compid() { - _impl_.compid_ = 0u; -} -inline ::uint32_t GetOurCompidResponse::compid() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp.GetOurCompidResponse.compid) - return _internal_compid(); -} -inline void GetOurCompidResponse::set_compid(::uint32_t value) { - _internal_set_compid(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.ftp.GetOurCompidResponse.compid) -} -inline ::uint32_t GetOurCompidResponse::_internal_compid() const { - return _impl_.compid_; -} -inline void GetOurCompidResponse::_internal_set_compid(::uint32_t value) { - ; - _impl_.compid_ = value; -} - -// ------------------------------------------------------------------- - // ProgressData // uint32 bytes_transferred = 1; diff --git a/src/mavsdk_server/src/generated/ftp_server/ftp_server.grpc.pb.cc b/src/mavsdk_server/src/generated/ftp_server/ftp_server.grpc.pb.cc new file mode 100644 index 0000000000..0cce74e863 --- /dev/null +++ b/src/mavsdk_server/src/generated/ftp_server/ftp_server.grpc.pb.cc @@ -0,0 +1,90 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: ftp_server/ftp_server.proto + +#include "ftp_server/ftp_server.pb.h" +#include "ftp_server/ftp_server.grpc.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace mavsdk { +namespace rpc { +namespace ftp_server { + +static const char* FtpServerService_method_names[] = { + "/mavsdk.rpc.ftp_server.FtpServerService/SetRootDir", +}; + +std::unique_ptr< FtpServerService::Stub> FtpServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { + (void)options; + std::unique_ptr< FtpServerService::Stub> stub(new FtpServerService::Stub(channel, options)); + return stub; +} + +FtpServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) + : channel_(channel), rpcmethod_SetRootDir_(FtpServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + {} + +::grpc::Status FtpServerService::Stub::SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetRootDir_, context, request, response); +} + +void FtpServerService::Stub::async::SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRootDir_, context, request, response, std::move(f)); +} + +void FtpServerService::Stub::async::SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRootDir_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>* FtpServerService::Stub::PrepareAsyncSetRootDirRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::ftp_server::SetRootDirResponse, ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetRootDir_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>* FtpServerService::Stub::AsyncSetRootDirRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetRootDirRaw(context, request, cq); + result->StartCall(); + return result; +} + +FtpServerService::Service::Service() { + AddMethod(new ::grpc::internal::RpcServiceMethod( + FtpServerService_method_names[0], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< FtpServerService::Service, ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](FtpServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::ftp_server::SetRootDirRequest* req, + ::mavsdk::rpc::ftp_server::SetRootDirResponse* resp) { + return service->SetRootDir(ctx, req, resp); + }, this))); +} + +FtpServerService::Service::~Service() { +} + +::grpc::Status FtpServerService::Service::SetRootDir(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + + +} // namespace mavsdk +} // namespace rpc +} // namespace ftp_server + diff --git a/src/mavsdk_server/src/generated/ftp_server/ftp_server.grpc.pb.h b/src/mavsdk_server/src/generated/ftp_server/ftp_server.grpc.pb.h new file mode 100644 index 0000000000..a95d49d16a --- /dev/null +++ b/src/mavsdk_server/src/generated/ftp_server/ftp_server.grpc.pb.h @@ -0,0 +1,266 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: ftp_server/ftp_server.proto +#ifndef GRPC_ftp_5fserver_2fftp_5fserver_2eproto__INCLUDED +#define GRPC_ftp_5fserver_2fftp_5fserver_2eproto__INCLUDED + +#include "ftp_server/ftp_server.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace rpc { +namespace ftp_server { + +// Provide files or directories to transfer. +class FtpServerService final { + public: + static constexpr char const* service_full_name() { + return "mavsdk.rpc.ftp_server.FtpServerService"; + } + class StubInterface { + public: + virtual ~StubInterface() {} + // + // Set root directory. + // + // This is the directory that can then be accessed by a client. + // The directory needs to exist when this is called. + // The permissions are the same as the file permission for the user running the server. + // The root directory can't be changed while an FTP process is in progress. + virtual ::grpc::Status SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp_server::SetRootDirResponse>> AsyncSetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp_server::SetRootDirResponse>>(AsyncSetRootDirRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp_server::SetRootDirResponse>> PrepareAsyncSetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp_server::SetRootDirResponse>>(PrepareAsyncSetRootDirRaw(context, request, cq)); + } + class async_interface { + public: + virtual ~async_interface() {} + // + // Set root directory. + // + // This is the directory that can then be accessed by a client. + // The directory needs to exist when this is called. + // The permissions are the same as the file permission for the user running the server. + // The root directory can't be changed while an FTP process is in progress. + virtual void SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response, std::function) = 0; + virtual void SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + }; + typedef class async_interface experimental_async_interface; + virtual class async_interface* async() { return nullptr; } + class async_interface* experimental_async() { return async(); } + private: + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp_server::SetRootDirResponse>* AsyncSetRootDirRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::ftp_server::SetRootDirResponse>* PrepareAsyncSetRootDirRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) = 0; + }; + class Stub final : public StubInterface { + public: + Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + ::grpc::Status SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>> AsyncSetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>>(AsyncSetRootDirRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>> PrepareAsyncSetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>>(PrepareAsyncSetRootDirRaw(context, request, cq)); + } + class async final : + public StubInterface::async_interface { + public: + void SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response, std::function) override; + void SetRootDir(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + private: + friend class Stub; + explicit async(Stub* stub): stub_(stub) { } + Stub* stub() { return stub_; } + Stub* stub_; + }; + class async* async() override { return &async_stub_; } + + private: + std::shared_ptr< ::grpc::ChannelInterface> channel_; + class async async_stub_{this}; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>* AsyncSetRootDirRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::ftp_server::SetRootDirResponse>* PrepareAsyncSetRootDirRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_SetRootDir_; + }; + static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + + class Service : public ::grpc::Service { + public: + Service(); + virtual ~Service(); + // + // Set root directory. + // + // This is the directory that can then be accessed by a client. + // The directory needs to exist when this is called. + // The permissions are the same as the file permission for the user running the server. + // The root directory can't be changed while an FTP process is in progress. + virtual ::grpc::Status SetRootDir(::grpc::ServerContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response); + }; + template + class WithAsyncMethod_SetRootDir : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetRootDir() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_SetRootDir() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRootDir(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* /*request*/, ::mavsdk::rpc::ftp_server::SetRootDirResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetRootDir(::grpc::ServerContext* context, ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::ftp_server::SetRootDirResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetRootDir AsyncService; + template + class WithCallbackMethod_SetRootDir : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetRootDir() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* request, ::mavsdk::rpc::ftp_server::SetRootDirResponse* response) { return this->SetRootDir(context, request, response); }));} + void SetMessageAllocatorFor_SetRootDir( + ::grpc::MessageAllocator< ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetRootDir() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRootDir(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* /*request*/, ::mavsdk::rpc::ftp_server::SetRootDirResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetRootDir( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* /*request*/, ::mavsdk::rpc::ftp_server::SetRootDirResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetRootDir CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_SetRootDir : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetRootDir() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_SetRootDir() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRootDir(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* /*request*/, ::mavsdk::rpc::ftp_server::SetRootDirResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithRawMethod_SetRootDir : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetRootDir() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_SetRootDir() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRootDir(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* /*request*/, ::mavsdk::rpc::ftp_server::SetRootDirResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetRootDir(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawCallbackMethod_SetRootDir : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetRootDir() { + ::grpc::Service::MarkMethodRawCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRootDir(context, request, response); })); + } + ~WithRawCallbackMethod_SetRootDir() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRootDir(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* /*request*/, ::mavsdk::rpc::ftp_server::SetRootDirResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetRootDir( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithStreamedUnaryMethod_SetRootDir : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetRootDir() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::ftp_server::SetRootDirRequest, ::mavsdk::rpc::ftp_server::SetRootDirResponse>* streamer) { + return this->StreamedSetRootDir(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetRootDir() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetRootDir(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::ftp_server::SetRootDirRequest* /*request*/, ::mavsdk::rpc::ftp_server::SetRootDirResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetRootDir(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::ftp_server::SetRootDirRequest,::mavsdk::rpc::ftp_server::SetRootDirResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetRootDir StreamedUnaryService; + typedef Service SplitStreamedService; + typedef WithStreamedUnaryMethod_SetRootDir StreamedService; +}; + +} // namespace ftp_server +} // namespace rpc +} // namespace mavsdk + + +#endif // GRPC_ftp_5fserver_2fftp_5fserver_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/ftp_server/ftp_server.pb.cc b/src/mavsdk_server/src/generated/ftp_server/ftp_server.pb.cc new file mode 100644 index 0000000000..562d7b5b69 --- /dev/null +++ b/src/mavsdk_server/src/generated/ftp_server/ftp_server.pb.cc @@ -0,0 +1,867 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: ftp_server/ftp_server.proto + +#include "ftp_server/ftp_server.pb.h" + +#include +#include "google/protobuf/io/coded_stream.h" +#include "google/protobuf/extension_set.h" +#include "google/protobuf/wire_format_lite.h" +#include "google/protobuf/descriptor.h" +#include "google/protobuf/generated_message_reflection.h" +#include "google/protobuf/reflection_ops.h" +#include "google/protobuf/wire_format.h" +// @@protoc_insertion_point(includes) + +// Must be included last. +#include "google/protobuf/port_def.inc" +PROTOBUF_PRAGMA_INIT_SEG +namespace _pb = ::PROTOBUF_NAMESPACE_ID; +namespace _pbi = ::PROTOBUF_NAMESPACE_ID::internal; +namespace mavsdk { +namespace rpc { +namespace ftp_server { +template +PROTOBUF_CONSTEXPR SetRootDirRequest::SetRootDirRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.path_)*/ { + &::_pbi::fixed_address_empty_string, ::_pbi::ConstantInitialized {} + } + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct SetRootDirRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetRootDirRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetRootDirRequestDefaultTypeInternal() {} + union { + SetRootDirRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRootDirRequestDefaultTypeInternal _SetRootDirRequest_default_instance_; +template +PROTOBUF_CONSTEXPR SetRootDirResponse::SetRootDirResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.ftp_server_result_)*/nullptr} {} +struct SetRootDirResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetRootDirResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetRootDirResponseDefaultTypeInternal() {} + union { + SetRootDirResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRootDirResponseDefaultTypeInternal _SetRootDirResponse_default_instance_; +template +PROTOBUF_CONSTEXPR FtpServerResult::FtpServerResult( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.result_str_)*/ { + &::_pbi::fixed_address_empty_string, ::_pbi::ConstantInitialized {} + } + + , /*decltype(_impl_.result_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct FtpServerResultDefaultTypeInternal { + PROTOBUF_CONSTEXPR FtpServerResultDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FtpServerResultDefaultTypeInternal() {} + union { + FtpServerResult _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FtpServerResultDefaultTypeInternal _FtpServerResult_default_instance_; +} // namespace ftp_server +} // namespace rpc +} // namespace mavsdk +static ::_pb::Metadata file_level_metadata_ftp_5fserver_2fftp_5fserver_2eproto[3]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_ftp_5fserver_2fftp_5fserver_2eproto[1]; +static constexpr const ::_pb::ServiceDescriptor** + file_level_service_descriptors_ftp_5fserver_2fftp_5fserver_2eproto = nullptr; +const ::uint32_t TableStruct_ftp_5fserver_2fftp_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( + protodesc_cold) = { + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::SetRootDirRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::SetRootDirRequest, _impl_.path_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::SetRootDirResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::SetRootDirResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::SetRootDirResponse, _impl_.ftp_server_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::FtpServerResult, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::FtpServerResult, _impl_.result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::ftp_server::FtpServerResult, _impl_.result_str_), +}; + +static const ::_pbi::MigrationSchema + schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, -1, sizeof(::mavsdk::rpc::ftp_server::SetRootDirRequest)}, + { 9, 18, -1, sizeof(::mavsdk::rpc::ftp_server::SetRootDirResponse)}, + { 19, -1, -1, sizeof(::mavsdk::rpc::ftp_server::FtpServerResult)}, +}; + +static const ::_pb::Message* const file_default_instances[] = { + &::mavsdk::rpc::ftp_server::_SetRootDirRequest_default_instance_._instance, + &::mavsdk::rpc::ftp_server::_SetRootDirResponse_default_instance_._instance, + &::mavsdk::rpc::ftp_server::_FtpServerResult_default_instance_._instance, +}; +const char descriptor_table_protodef_ftp_5fserver_2fftp_5fserver_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + "\n\033ftp_server/ftp_server.proto\022\025mavsdk.rp" + "c.ftp_server\032\024mavsdk_options.proto\"!\n\021Se" + "tRootDirRequest\022\014\n\004path\030\001 \001(\t\"W\n\022SetRoot" + "DirResponse\022A\n\021ftp_server_result\030\001 \001(\0132&" + ".mavsdk.rpc.ftp_server.FtpServerResult\"\302" + "\001\n\017FtpServerResult\022=\n\006result\030\001 \001(\0162-.mav" + "sdk.rpc.ftp_server.FtpServerResult.Resul" + "t\022\022\n\nresult_str\030\002 \001(\t\"\\\n\006Result\022\022\n\016RESUL" + "T_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\031\n\025RESUL" + "T_DOES_NOT_EXIST\020\002\022\017\n\013RESULT_BUSY\020\0032{\n\020F" + "tpServerService\022g\n\nSetRootDir\022(.mavsdk.r" + "pc.ftp_server.SetRootDirRequest\032).mavsdk" + ".rpc.ftp_server.SetRootDirResponse\"\004\200\265\030\001" + "B&\n\024io.mavsdk.ftp_serverB\016FtpServerProto" + "b\006proto3" +}; +static const ::_pbi::DescriptorTable* const descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_deps[1] = + { + &::descriptor_table_mavsdk_5foptions_2eproto, +}; +static ::absl::once_flag descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_once; +const ::_pbi::DescriptorTable descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto = { + false, + false, + 568, + descriptor_table_protodef_ftp_5fserver_2fftp_5fserver_2eproto, + "ftp_server/ftp_server.proto", + &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_once, + descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_deps, + 1, + 3, + schemas, + file_default_instances, + TableStruct_ftp_5fserver_2fftp_5fserver_2eproto::offsets, + file_level_metadata_ftp_5fserver_2fftp_5fserver_2eproto, + file_level_enum_descriptors_ftp_5fserver_2fftp_5fserver_2eproto, + file_level_service_descriptors_ftp_5fserver_2fftp_5fserver_2eproto, +}; + +// This function exists to be marked as weak. +// It can significantly speed up compilation by breaking up LLVM's SCC +// in the .pb.cc translation units. Large translation units see a +// reduction of more than 35% of walltime for optimized builds. Without +// the weak attribute all the messages in the file, including all the +// vtables and everything they use become part of the same SCC through +// a cycle like: +// GetMetadata -> descriptor table -> default instances -> +// vtables -> GetMetadata +// By adding a weak function here we break the connection from the +// individual vtables back into the descriptor table. +PROTOBUF_ATTRIBUTE_WEAK const ::_pbi::DescriptorTable* descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_getter() { + return &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto; +} +// Force running AddDescriptors() at dynamic initialization time. +PROTOBUF_ATTRIBUTE_INIT_PRIORITY2 +static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_ftp_5fserver_2fftp_5fserver_2eproto(&descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto); +namespace mavsdk { +namespace rpc { +namespace ftp_server { +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* FtpServerResult_Result_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto); + return file_level_enum_descriptors_ftp_5fserver_2fftp_5fserver_2eproto[0]; +} +bool FtpServerResult_Result_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr FtpServerResult_Result FtpServerResult::RESULT_UNKNOWN; +constexpr FtpServerResult_Result FtpServerResult::RESULT_SUCCESS; +constexpr FtpServerResult_Result FtpServerResult::RESULT_DOES_NOT_EXIST; +constexpr FtpServerResult_Result FtpServerResult::RESULT_BUSY; +constexpr FtpServerResult_Result FtpServerResult::Result_MIN; +constexpr FtpServerResult_Result FtpServerResult::Result_MAX; +constexpr int FtpServerResult::Result_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +// =================================================================== + +class SetRootDirRequest::_Internal { + public: +}; + +SetRootDirRequest::SetRootDirRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp_server.SetRootDirRequest) +} +SetRootDirRequest::SetRootDirRequest(const SetRootDirRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + SetRootDirRequest* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_.path_) {} + + , /*decltype(_impl_._cached_size_)*/{}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + _impl_.path_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.path_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_path().empty()) { + _this->_impl_.path_.Set(from._internal_path(), _this->GetArenaForAllocation()); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp_server.SetRootDirRequest) +} + +inline void SetRootDirRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.path_) {} + + , /*decltype(_impl_._cached_size_)*/{} + }; + _impl_.path_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.path_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING +} + +SetRootDirRequest::~SetRootDirRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp_server.SetRootDirRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetRootDirRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + _impl_.path_.Destroy(); +} + +void SetRootDirRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void SetRootDirRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp_server.SetRootDirRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.path_.ClearToEmpty(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetRootDirRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // string path = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + auto str = _internal_mutable_path(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.ftp_server.SetRootDirRequest.path")); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* SetRootDirRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp_server.SetRootDirRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // string path = 1; + if (!this->_internal_path().empty()) { + const std::string& _s = this->_internal_path(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.ftp_server.SetRootDirRequest.path"); + target = stream->WriteStringMaybeAliased(1, _s, target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp_server.SetRootDirRequest) + return target; +} + +::size_t SetRootDirRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp_server.SetRootDirRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string path = 1; + if (!this->_internal_path().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_path()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetRootDirRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + SetRootDirRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetRootDirRequest::GetClassData() const { return &_class_data_; } + + +void SetRootDirRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp_server.SetRootDirRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_path().empty()) { + _this->_internal_set_path(from._internal_path()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetRootDirRequest::CopyFrom(const SetRootDirRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp_server.SetRootDirRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetRootDirRequest::IsInitialized() const { + return true; +} + +void SetRootDirRequest::InternalSwap(SetRootDirRequest* other) { + using std::swap; + auto* lhs_arena = GetArenaForAllocation(); + auto* rhs_arena = other->GetArenaForAllocation(); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.path_, lhs_arena, + &other->_impl_.path_, rhs_arena); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetRootDirRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_getter, &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_once, + file_level_metadata_ftp_5fserver_2fftp_5fserver_2eproto[0]); +} +// =================================================================== + +class SetRootDirResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(SetRootDirResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::ftp_server::FtpServerResult& ftp_server_result(const SetRootDirResponse* msg); + static void set_has_ftp_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::ftp_server::FtpServerResult& +SetRootDirResponse::_Internal::ftp_server_result(const SetRootDirResponse* msg) { + return *msg->_impl_.ftp_server_result_; +} +SetRootDirResponse::SetRootDirResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp_server.SetRootDirResponse) +} +SetRootDirResponse::SetRootDirResponse(const SetRootDirResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + SetRootDirResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.ftp_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.ftp_server_result_ = new ::mavsdk::rpc::ftp_server::FtpServerResult(*from._impl_.ftp_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp_server.SetRootDirResponse) +} + +inline void SetRootDirResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.ftp_server_result_){nullptr} + }; +} + +SetRootDirResponse::~SetRootDirResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp_server.SetRootDirResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetRootDirResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.ftp_server_result_; +} + +void SetRootDirResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void SetRootDirResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp_server.SetRootDirResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.ftp_server_result_ != nullptr); + _impl_.ftp_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetRootDirResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.ftp_server.FtpServerResult ftp_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_ftp_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* SetRootDirResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp_server.SetRootDirResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.ftp_server.FtpServerResult ftp_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::ftp_server_result(this), + _Internal::ftp_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp_server.SetRootDirResponse) + return target; +} + +::size_t SetRootDirResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp_server.SetRootDirResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.ftp_server.FtpServerResult ftp_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.ftp_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetRootDirResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + SetRootDirResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetRootDirResponse::GetClassData() const { return &_class_data_; } + + +void SetRootDirResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp_server.SetRootDirResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_ftp_server_result()->::mavsdk::rpc::ftp_server::FtpServerResult::MergeFrom( + from._internal_ftp_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetRootDirResponse::CopyFrom(const SetRootDirResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp_server.SetRootDirResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetRootDirResponse::IsInitialized() const { + return true; +} + +void SetRootDirResponse::InternalSwap(SetRootDirResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.ftp_server_result_, other->_impl_.ftp_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetRootDirResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_getter, &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_once, + file_level_metadata_ftp_5fserver_2fftp_5fserver_2eproto[1]); +} +// =================================================================== + +class FtpServerResult::_Internal { + public: +}; + +FtpServerResult::FtpServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.ftp_server.FtpServerResult) +} +FtpServerResult::FtpServerResult(const FtpServerResult& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + FtpServerResult* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_.result_str_) {} + + , decltype(_impl_.result_) {} + + , /*decltype(_impl_._cached_size_)*/{}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + _impl_.result_str_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.result_str_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_result_str().empty()) { + _this->_impl_.result_str_.Set(from._internal_result_str(), _this->GetArenaForAllocation()); + } + _this->_impl_.result_ = from._impl_.result_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.ftp_server.FtpServerResult) +} + +inline void FtpServerResult::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.result_str_) {} + + , decltype(_impl_.result_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; + _impl_.result_str_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.result_str_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING +} + +FtpServerResult::~FtpServerResult() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.ftp_server.FtpServerResult) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void FtpServerResult::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + _impl_.result_str_.Destroy(); +} + +void FtpServerResult::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void FtpServerResult::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.ftp_server.FtpServerResult) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.result_str_.ClearToEmpty(); + _impl_.result_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* FtpServerResult::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.ftp_server.FtpServerResult.Result result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_result(static_cast<::mavsdk::rpc::ftp_server::FtpServerResult_Result>(val)); + } else { + goto handle_unusual; + } + continue; + // string result_str = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + auto str = _internal_mutable_result_str(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.ftp_server.FtpServerResult.result_str")); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* FtpServerResult::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.ftp_server.FtpServerResult) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.ftp_server.FtpServerResult.Result result = 1; + if (this->_internal_result() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_result(), target); + } + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + const std::string& _s = this->_internal_result_str(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.ftp_server.FtpServerResult.result_str"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.ftp_server.FtpServerResult) + return target; +} + +::size_t FtpServerResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.ftp_server.FtpServerResult) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_result_str()); + } + + // .mavsdk.rpc.ftp_server.FtpServerResult.Result result = 1; + if (this->_internal_result() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_result()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData FtpServerResult::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + FtpServerResult::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*FtpServerResult::GetClassData() const { return &_class_data_; } + + +void FtpServerResult::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.ftp_server.FtpServerResult) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_result_str().empty()) { + _this->_internal_set_result_str(from._internal_result_str()); + } + if (from._internal_result() != 0) { + _this->_internal_set_result(from._internal_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void FtpServerResult::CopyFrom(const FtpServerResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.ftp_server.FtpServerResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool FtpServerResult::IsInitialized() const { + return true; +} + +void FtpServerResult::InternalSwap(FtpServerResult* other) { + using std::swap; + auto* lhs_arena = GetArenaForAllocation(); + auto* rhs_arena = other->GetArenaForAllocation(); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.result_str_, lhs_arena, + &other->_impl_.result_str_, rhs_arena); + swap(_impl_.result_, other->_impl_.result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata FtpServerResult::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_getter, &descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto_once, + file_level_metadata_ftp_5fserver_2fftp_5fserver_2eproto[2]); +} +// @@protoc_insertion_point(namespace_scope) +} // namespace ftp_server +} // namespace rpc +} // namespace mavsdk +PROTOBUF_NAMESPACE_OPEN +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp_server::SetRootDirRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp_server::SetRootDirRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp_server::SetRootDirRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp_server::SetRootDirResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp_server::SetRootDirResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp_server::SetRootDirResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::ftp_server::FtpServerResult* +Arena::CreateMaybeMessage< ::mavsdk::rpc::ftp_server::FtpServerResult >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::ftp_server::FtpServerResult >(arena); +} +PROTOBUF_NAMESPACE_CLOSE +// @@protoc_insertion_point(global_scope) +#include "google/protobuf/port_undef.inc" diff --git a/src/mavsdk_server/src/generated/ftp_server/ftp_server.pb.h b/src/mavsdk_server/src/generated/ftp_server/ftp_server.pb.h new file mode 100644 index 0000000000..4b92b2b9d2 --- /dev/null +++ b/src/mavsdk_server/src/generated/ftp_server/ftp_server.pb.h @@ -0,0 +1,896 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: ftp_server/ftp_server.proto + +#ifndef GOOGLE_PROTOBUF_INCLUDED_ftp_5fserver_2fftp_5fserver_2eproto_2epb_2eh +#define GOOGLE_PROTOBUF_INCLUDED_ftp_5fserver_2fftp_5fserver_2eproto_2epb_2eh + +#include +#include +#include + +#include "google/protobuf/port_def.inc" +#if PROTOBUF_VERSION < 4023000 +#error "This file was generated by a newer version of protoc which is" +#error "incompatible with your Protocol Buffer headers. Please update" +#error "your headers." +#endif // PROTOBUF_VERSION + +#if 4023002 < PROTOBUF_MIN_PROTOC_VERSION +#error "This file was generated by an older version of protoc which is" +#error "incompatible with your Protocol Buffer headers. Please" +#error "regenerate this file with a newer version of protoc." +#endif // PROTOBUF_MIN_PROTOC_VERSION +#include "google/protobuf/port_undef.inc" +#include "google/protobuf/io/coded_stream.h" +#include "google/protobuf/arena.h" +#include "google/protobuf/arenastring.h" +#include "google/protobuf/generated_message_util.h" +#include "google/protobuf/metadata_lite.h" +#include "google/protobuf/generated_message_reflection.h" +#include "google/protobuf/message.h" +#include "google/protobuf/repeated_field.h" // IWYU pragma: export +#include "google/protobuf/extension_set.h" // IWYU pragma: export +#include "google/protobuf/generated_enum_reflection.h" +#include "google/protobuf/unknown_field_set.h" +#include "mavsdk_options.pb.h" +// @@protoc_insertion_point(includes) + +// Must be included last. +#include "google/protobuf/port_def.inc" + +#define PROTOBUF_INTERNAL_EXPORT_ftp_5fserver_2fftp_5fserver_2eproto + +PROTOBUF_NAMESPACE_OPEN +namespace internal { +class AnyMetadata; +} // namespace internal +PROTOBUF_NAMESPACE_CLOSE + +// Internal implementation detail -- do not use these members. +struct TableStruct_ftp_5fserver_2fftp_5fserver_2eproto { + static const ::uint32_t offsets[]; +}; +extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable + descriptor_table_ftp_5fserver_2fftp_5fserver_2eproto; +namespace mavsdk { +namespace rpc { +namespace ftp_server { +class FtpServerResult; +struct FtpServerResultDefaultTypeInternal; +extern FtpServerResultDefaultTypeInternal _FtpServerResult_default_instance_; +class SetRootDirRequest; +struct SetRootDirRequestDefaultTypeInternal; +extern SetRootDirRequestDefaultTypeInternal _SetRootDirRequest_default_instance_; +class SetRootDirResponse; +struct SetRootDirResponseDefaultTypeInternal; +extern SetRootDirResponseDefaultTypeInternal _SetRootDirResponse_default_instance_; +} // namespace ftp_server +} // namespace rpc +} // namespace mavsdk +PROTOBUF_NAMESPACE_OPEN +template <> +::mavsdk::rpc::ftp_server::FtpServerResult* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp_server::FtpServerResult>(Arena*); +template <> +::mavsdk::rpc::ftp_server::SetRootDirRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp_server::SetRootDirRequest>(Arena*); +template <> +::mavsdk::rpc::ftp_server::SetRootDirResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::ftp_server::SetRootDirResponse>(Arena*); +PROTOBUF_NAMESPACE_CLOSE + +namespace mavsdk { +namespace rpc { +namespace ftp_server { +enum FtpServerResult_Result : int { + FtpServerResult_Result_RESULT_UNKNOWN = 0, + FtpServerResult_Result_RESULT_SUCCESS = 1, + FtpServerResult_Result_RESULT_DOES_NOT_EXIST = 2, + FtpServerResult_Result_RESULT_BUSY = 3, + FtpServerResult_Result_FtpServerResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + FtpServerResult_Result_FtpServerResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool FtpServerResult_Result_IsValid(int value); +constexpr FtpServerResult_Result FtpServerResult_Result_Result_MIN = static_cast(0); +constexpr FtpServerResult_Result FtpServerResult_Result_Result_MAX = static_cast(3); +constexpr int FtpServerResult_Result_Result_ARRAYSIZE = 3 + 1; +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* +FtpServerResult_Result_descriptor(); +template +const std::string& FtpServerResult_Result_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to Result_Name()."); + return FtpServerResult_Result_Name(static_cast(value)); +} +template <> +inline const std::string& FtpServerResult_Result_Name(FtpServerResult_Result value) { + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool FtpServerResult_Result_Parse(absl::string_view name, FtpServerResult_Result* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + FtpServerResult_Result_descriptor(), name, value); +} + +// =================================================================== + + +// ------------------------------------------------------------------- + +class SetRootDirRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp_server.SetRootDirRequest) */ { + public: + inline SetRootDirRequest() : SetRootDirRequest(nullptr) {} + ~SetRootDirRequest() override; + template + explicit PROTOBUF_CONSTEXPR SetRootDirRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetRootDirRequest(const SetRootDirRequest& from); + SetRootDirRequest(SetRootDirRequest&& from) noexcept + : SetRootDirRequest() { + *this = ::std::move(from); + } + + inline SetRootDirRequest& operator=(const SetRootDirRequest& from) { + CopyFrom(from); + return *this; + } + inline SetRootDirRequest& operator=(SetRootDirRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetRootDirRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetRootDirRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRootDirRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(SetRootDirRequest& a, SetRootDirRequest& b) { + a.Swap(&b); + } + inline void Swap(SetRootDirRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetRootDirRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetRootDirRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetRootDirRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const SetRootDirRequest& from) { + SetRootDirRequest::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetRootDirRequest* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.ftp_server.SetRootDirRequest"; + } + protected: + explicit SetRootDirRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kPathFieldNumber = 1, + }; + // string path = 1; + void clear_path() ; + const std::string& path() const; + + + + + template + void set_path(Arg_&& arg, Args_... args); + std::string* mutable_path(); + PROTOBUF_NODISCARD std::string* release_path(); + void set_allocated_path(std::string* ptr); + + private: + const std::string& _internal_path() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_path( + const std::string& value); + std::string* _internal_mutable_path(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp_server.SetRootDirRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr path_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_ftp_5fserver_2fftp_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SetRootDirResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp_server.SetRootDirResponse) */ { + public: + inline SetRootDirResponse() : SetRootDirResponse(nullptr) {} + ~SetRootDirResponse() override; + template + explicit PROTOBUF_CONSTEXPR SetRootDirResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetRootDirResponse(const SetRootDirResponse& from); + SetRootDirResponse(SetRootDirResponse&& from) noexcept + : SetRootDirResponse() { + *this = ::std::move(from); + } + + inline SetRootDirResponse& operator=(const SetRootDirResponse& from) { + CopyFrom(from); + return *this; + } + inline SetRootDirResponse& operator=(SetRootDirResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetRootDirResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetRootDirResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRootDirResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(SetRootDirResponse& a, SetRootDirResponse& b) { + a.Swap(&b); + } + inline void Swap(SetRootDirResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetRootDirResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetRootDirResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetRootDirResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const SetRootDirResponse& from) { + SetRootDirResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetRootDirResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.ftp_server.SetRootDirResponse"; + } + protected: + explicit SetRootDirResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kFtpServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.ftp_server.FtpServerResult ftp_server_result = 1; + bool has_ftp_server_result() const; + void clear_ftp_server_result() ; + const ::mavsdk::rpc::ftp_server::FtpServerResult& ftp_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::ftp_server::FtpServerResult* release_ftp_server_result(); + ::mavsdk::rpc::ftp_server::FtpServerResult* mutable_ftp_server_result(); + void set_allocated_ftp_server_result(::mavsdk::rpc::ftp_server::FtpServerResult* ftp_server_result); + private: + const ::mavsdk::rpc::ftp_server::FtpServerResult& _internal_ftp_server_result() const; + ::mavsdk::rpc::ftp_server::FtpServerResult* _internal_mutable_ftp_server_result(); + public: + void unsafe_arena_set_allocated_ftp_server_result( + ::mavsdk::rpc::ftp_server::FtpServerResult* ftp_server_result); + ::mavsdk::rpc::ftp_server::FtpServerResult* unsafe_arena_release_ftp_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp_server.SetRootDirResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::ftp_server::FtpServerResult* ftp_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_ftp_5fserver_2fftp_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class FtpServerResult final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.ftp_server.FtpServerResult) */ { + public: + inline FtpServerResult() : FtpServerResult(nullptr) {} + ~FtpServerResult() override; + template + explicit PROTOBUF_CONSTEXPR FtpServerResult(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + FtpServerResult(const FtpServerResult& from); + FtpServerResult(FtpServerResult&& from) noexcept + : FtpServerResult() { + *this = ::std::move(from); + } + + inline FtpServerResult& operator=(const FtpServerResult& from) { + CopyFrom(from); + return *this; + } + inline FtpServerResult& operator=(FtpServerResult&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const FtpServerResult& default_instance() { + return *internal_default_instance(); + } + static inline const FtpServerResult* internal_default_instance() { + return reinterpret_cast( + &_FtpServerResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(FtpServerResult& a, FtpServerResult& b) { + a.Swap(&b); + } + inline void Swap(FtpServerResult* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(FtpServerResult* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + FtpServerResult* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const FtpServerResult& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const FtpServerResult& from) { + FtpServerResult::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(FtpServerResult* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.ftp_server.FtpServerResult"; + } + protected: + explicit FtpServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + using Result = FtpServerResult_Result; + static constexpr Result RESULT_UNKNOWN = FtpServerResult_Result_RESULT_UNKNOWN; + static constexpr Result RESULT_SUCCESS = FtpServerResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_DOES_NOT_EXIST = FtpServerResult_Result_RESULT_DOES_NOT_EXIST; + static constexpr Result RESULT_BUSY = FtpServerResult_Result_RESULT_BUSY; + static inline bool Result_IsValid(int value) { + return FtpServerResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = FtpServerResult_Result_Result_MIN; + static constexpr Result Result_MAX = FtpServerResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = FtpServerResult_Result_Result_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* Result_descriptor() { + return FtpServerResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T value) { + return FtpServerResult_Result_Name(value); + } + static inline bool Result_Parse(absl::string_view name, Result* value) { + return FtpServerResult_Result_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + enum : int { + kResultStrFieldNumber = 2, + kResultFieldNumber = 1, + }; + // string result_str = 2; + void clear_result_str() ; + const std::string& result_str() const; + + + + + template + void set_result_str(Arg_&& arg, Args_... args); + std::string* mutable_result_str(); + PROTOBUF_NODISCARD std::string* release_result_str(); + void set_allocated_result_str(std::string* ptr); + + private: + const std::string& _internal_result_str() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_result_str( + const std::string& value); + std::string* _internal_mutable_result_str(); + + public: + // .mavsdk.rpc.ftp_server.FtpServerResult.Result result = 1; + void clear_result() ; + ::mavsdk::rpc::ftp_server::FtpServerResult_Result result() const; + void set_result(::mavsdk::rpc::ftp_server::FtpServerResult_Result value); + + private: + ::mavsdk::rpc::ftp_server::FtpServerResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::ftp_server::FtpServerResult_Result value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp_server.FtpServerResult) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr result_str_; + int result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_ftp_5fserver_2fftp_5fserver_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// SetRootDirRequest + +// string path = 1; +inline void SetRootDirRequest::clear_path() { + _impl_.path_.ClearToEmpty(); +} +inline const std::string& SetRootDirRequest::path() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp_server.SetRootDirRequest.path) + return _internal_path(); +} +template +inline PROTOBUF_ALWAYS_INLINE void SetRootDirRequest::set_path(Arg_&& arg, + Args_... args) { + ; + _impl_.path_.Set(static_cast(arg), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.ftp_server.SetRootDirRequest.path) +} +inline std::string* SetRootDirRequest::mutable_path() { + std::string* _s = _internal_mutable_path(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.ftp_server.SetRootDirRequest.path) + return _s; +} +inline const std::string& SetRootDirRequest::_internal_path() const { + return _impl_.path_.Get(); +} +inline void SetRootDirRequest::_internal_set_path(const std::string& value) { + ; + + + _impl_.path_.Set(value, GetArenaForAllocation()); +} +inline std::string* SetRootDirRequest::_internal_mutable_path() { + ; + return _impl_.path_.Mutable( GetArenaForAllocation()); +} +inline std::string* SetRootDirRequest::release_path() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.ftp_server.SetRootDirRequest.path) + return _impl_.path_.Release(); +} +inline void SetRootDirRequest::set_allocated_path(std::string* value) { + _impl_.path_.SetAllocated(value, GetArenaForAllocation()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.path_.IsDefault()) { + _impl_.path_.Set("", GetArenaForAllocation()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.ftp_server.SetRootDirRequest.path) +} + +// ------------------------------------------------------------------- + +// SetRootDirResponse + +// .mavsdk.rpc.ftp_server.FtpServerResult ftp_server_result = 1; +inline bool SetRootDirResponse::has_ftp_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.ftp_server_result_ != nullptr); + return value; +} +inline void SetRootDirResponse::clear_ftp_server_result() { + if (_impl_.ftp_server_result_ != nullptr) _impl_.ftp_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::ftp_server::FtpServerResult& SetRootDirResponse::_internal_ftp_server_result() const { + const ::mavsdk::rpc::ftp_server::FtpServerResult* p = _impl_.ftp_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::ftp_server::_FtpServerResult_default_instance_); +} +inline const ::mavsdk::rpc::ftp_server::FtpServerResult& SetRootDirResponse::ftp_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp_server.SetRootDirResponse.ftp_server_result) + return _internal_ftp_server_result(); +} +inline void SetRootDirResponse::unsafe_arena_set_allocated_ftp_server_result( + ::mavsdk::rpc::ftp_server::FtpServerResult* ftp_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.ftp_server_result_); + } + _impl_.ftp_server_result_ = ftp_server_result; + if (ftp_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.ftp_server.SetRootDirResponse.ftp_server_result) +} +inline ::mavsdk::rpc::ftp_server::FtpServerResult* SetRootDirResponse::release_ftp_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::ftp_server::FtpServerResult* temp = _impl_.ftp_server_result_; + _impl_.ftp_server_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::ftp_server::FtpServerResult* SetRootDirResponse::unsafe_arena_release_ftp_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.ftp_server.SetRootDirResponse.ftp_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::ftp_server::FtpServerResult* temp = _impl_.ftp_server_result_; + _impl_.ftp_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::ftp_server::FtpServerResult* SetRootDirResponse::_internal_mutable_ftp_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.ftp_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::ftp_server::FtpServerResult>(GetArenaForAllocation()); + _impl_.ftp_server_result_ = p; + } + return _impl_.ftp_server_result_; +} +inline ::mavsdk::rpc::ftp_server::FtpServerResult* SetRootDirResponse::mutable_ftp_server_result() { + ::mavsdk::rpc::ftp_server::FtpServerResult* _msg = _internal_mutable_ftp_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.ftp_server.SetRootDirResponse.ftp_server_result) + return _msg; +} +inline void SetRootDirResponse::set_allocated_ftp_server_result(::mavsdk::rpc::ftp_server::FtpServerResult* ftp_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.ftp_server_result_; + } + if (ftp_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(ftp_server_result); + if (message_arena != submessage_arena) { + ftp_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, ftp_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.ftp_server_result_ = ftp_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.ftp_server.SetRootDirResponse.ftp_server_result) +} + +// ------------------------------------------------------------------- + +// FtpServerResult + +// .mavsdk.rpc.ftp_server.FtpServerResult.Result result = 1; +inline void FtpServerResult::clear_result() { + _impl_.result_ = 0; +} +inline ::mavsdk::rpc::ftp_server::FtpServerResult_Result FtpServerResult::result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp_server.FtpServerResult.result) + return _internal_result(); +} +inline void FtpServerResult::set_result(::mavsdk::rpc::ftp_server::FtpServerResult_Result value) { + _internal_set_result(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.ftp_server.FtpServerResult.result) +} +inline ::mavsdk::rpc::ftp_server::FtpServerResult_Result FtpServerResult::_internal_result() const { + return static_cast<::mavsdk::rpc::ftp_server::FtpServerResult_Result>(_impl_.result_); +} +inline void FtpServerResult::_internal_set_result(::mavsdk::rpc::ftp_server::FtpServerResult_Result value) { + ; + _impl_.result_ = value; +} + +// string result_str = 2; +inline void FtpServerResult::clear_result_str() { + _impl_.result_str_.ClearToEmpty(); +} +inline const std::string& FtpServerResult::result_str() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.ftp_server.FtpServerResult.result_str) + return _internal_result_str(); +} +template +inline PROTOBUF_ALWAYS_INLINE void FtpServerResult::set_result_str(Arg_&& arg, + Args_... args) { + ; + _impl_.result_str_.Set(static_cast(arg), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.ftp_server.FtpServerResult.result_str) +} +inline std::string* FtpServerResult::mutable_result_str() { + std::string* _s = _internal_mutable_result_str(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.ftp_server.FtpServerResult.result_str) + return _s; +} +inline const std::string& FtpServerResult::_internal_result_str() const { + return _impl_.result_str_.Get(); +} +inline void FtpServerResult::_internal_set_result_str(const std::string& value) { + ; + + + _impl_.result_str_.Set(value, GetArenaForAllocation()); +} +inline std::string* FtpServerResult::_internal_mutable_result_str() { + ; + return _impl_.result_str_.Mutable( GetArenaForAllocation()); +} +inline std::string* FtpServerResult::release_result_str() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.ftp_server.FtpServerResult.result_str) + return _impl_.result_str_.Release(); +} +inline void FtpServerResult::set_allocated_result_str(std::string* value) { + _impl_.result_str_.SetAllocated(value, GetArenaForAllocation()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.result_str_.IsDefault()) { + _impl_.result_str_.Set("", GetArenaForAllocation()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.ftp_server.FtpServerResult.result_str) +} + +#ifdef __GNUC__ +#pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) +} // namespace ftp_server +} // namespace rpc +} // namespace mavsdk + + +PROTOBUF_NAMESPACE_OPEN + +template <> +struct is_proto_enum<::mavsdk::rpc::ftp_server::FtpServerResult_Result> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::ftp_server::FtpServerResult_Result>() { + return ::mavsdk::rpc::ftp_server::FtpServerResult_Result_descriptor(); +} + +PROTOBUF_NAMESPACE_CLOSE + +// @@protoc_insertion_point(global_scope) + +#include "google/protobuf/port_undef.inc" + +#endif // GOOGLE_PROTOBUF_INCLUDED_ftp_5fserver_2fftp_5fserver_2eproto_2epb_2eh diff --git a/src/mavsdk_server/src/grpc_server.cpp b/src/mavsdk_server/src/grpc_server.cpp index cc6c71907e..ffb1b02045 100644 --- a/src/mavsdk_server/src/grpc_server.cpp +++ b/src/mavsdk_server/src/grpc_server.cpp @@ -62,6 +62,10 @@ int GrpcServer::run() builder.RegisterService(&_ftp_service); #endif +#ifdef FTP_SERVER_ENABLED + builder.RegisterService(&_ftp_server_service); +#endif + #ifdef GEOFENCE_ENABLED builder.RegisterService(&_geofence_service); #endif @@ -221,6 +225,10 @@ void GrpcServer::stop() _ftp_service.stop(); #endif +#ifdef FTP_SERVER_ENABLED + _ftp_server_service.stop(); +#endif + #ifdef GEOFENCE_ENABLED _geofence_service.stop(); #endif diff --git a/src/mavsdk_server/src/grpc_server.h b/src/mavsdk_server/src/grpc_server.h index 4ca514a13c..9842b37984 100644 --- a/src/mavsdk_server/src/grpc_server.h +++ b/src/mavsdk_server/src/grpc_server.h @@ -64,6 +64,11 @@ #include "ftp/ftp_service_impl.h" #endif +#ifdef FTP_SERVER_ENABLED +#include "plugins/ftp_server/ftp_server.h" +#include "ftp_server/ftp_server_service_impl.h" +#endif + #ifdef GEOFENCE_ENABLED #include "plugins/geofence/geofence.h" #include "geofence/geofence_service_impl.h" @@ -232,6 +237,11 @@ class GrpcServer { _ftp_service(_ftp_lazy_plugin), #endif +#ifdef FTP_SERVER_ENABLED + _ftp_server_lazy_plugin(mavsdk), + _ftp_server_service(_ftp_server_lazy_plugin), +#endif + #ifdef GEOFENCE_ENABLED _geofence_lazy_plugin(mavsdk), _geofence_service(_geofence_lazy_plugin), @@ -424,6 +434,13 @@ class GrpcServer { FtpServiceImpl<> _ftp_service; #endif +#ifdef FTP_SERVER_ENABLED + + LazyServerPlugin _ftp_server_lazy_plugin; + + FtpServerServiceImpl<> _ftp_server_service; +#endif + #ifdef GEOFENCE_ENABLED LazyPlugin _geofence_lazy_plugin; diff --git a/src/mavsdk_server/src/plugins/ftp/ftp_service_impl.h b/src/mavsdk_server/src/plugins/ftp/ftp_service_impl.h index 6874dba81f..a818afd9b5 100644 --- a/src/mavsdk_server/src/plugins/ftp/ftp_service_impl.h +++ b/src/mavsdk_server/src/plugins/ftp/ftp_service_impl.h @@ -135,34 +135,6 @@ class FtpServiceImpl final : public rpc::ftp::FtpService::Service { } } - grpc::Status Reset( - grpc::ServerContext* /* context */, - const rpc::ftp::ResetRequest* /* request */, - rpc::ftp::ResetResponse* response) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - if (response != nullptr) { - auto result = mavsdk::Ftp::Result::NoSystem; - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - - std::promise prom; - std::future fut = prom.get_future(); - - _lazy_plugin.maybe_plugin()->reset_async( - [&prom](const mavsdk::Ftp::Result result) { prom.set_value(result); }); - auto result = fut.get(); - - if (response != nullptr) { - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - grpc::Status SubscribeDownload( grpc::ServerContext* /* context */, const mavsdk::rpc::ftp::SubscribeDownloadRequest* request, @@ -187,6 +159,7 @@ class FtpServiceImpl final : public rpc::ftp::FtpService::Service { _lazy_plugin.maybe_plugin()->download_async( request->remote_file_path(), request->local_dir(), + request->use_burst(), [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex]( mavsdk::Ftp::Result result, const mavsdk::Ftp::ProgressData download) { rpc::ftp::DownloadResponse rpc_response; @@ -447,34 +420,6 @@ class FtpServiceImpl final : public rpc::ftp::FtpService::Service { return grpc::Status::OK; } - grpc::Status SetRootDirectory( - grpc::ServerContext* /* context */, - const rpc::ftp::SetRootDirectoryRequest* request, - rpc::ftp::SetRootDirectoryResponse* response) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - if (response != nullptr) { - auto result = mavsdk::Ftp::Result::NoSystem; - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - - if (request == nullptr) { - LogWarn() << "SetRootDirectory sent with a null request! Ignoring..."; - return grpc::Status::OK; - } - - auto result = _lazy_plugin.maybe_plugin()->set_root_directory(request->root_dir()); - - if (response != nullptr) { - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - grpc::Status SetTargetCompid( grpc::ServerContext* /* context */, const rpc::ftp::SetTargetCompidRequest* request, @@ -503,24 +448,6 @@ class FtpServiceImpl final : public rpc::ftp::FtpService::Service { return grpc::Status::OK; } - grpc::Status GetOurCompid( - grpc::ServerContext* /* context */, - const rpc::ftp::GetOurCompidRequest* /* request */, - rpc::ftp::GetOurCompidResponse* response) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - return grpc::Status::OK; - } - - auto result = _lazy_plugin.maybe_plugin()->get_our_compid(); - - if (response != nullptr) { - response->set_compid(result); - } - - return grpc::Status::OK; - } - void stop() { _stopped.store(true); diff --git a/src/mavsdk_server/src/plugins/ftp_server/ftp_server_service_impl.h b/src/mavsdk_server/src/plugins/ftp_server/ftp_server_service_impl.h new file mode 100644 index 0000000000..2d12734ec0 --- /dev/null +++ b/src/mavsdk_server/src/plugins/ftp_server/ftp_server_service_impl.h @@ -0,0 +1,152 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/ftp_server/ftp_server.proto) + +#include "ftp_server/ftp_server.grpc.pb.h" +#include "plugins/ftp_server/ftp_server.h" + +#include "mavsdk.h" + +#include "lazy_server_plugin.h" + +#include "log.h" +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace mavsdk_server { + +template> + +class FtpServerServiceImpl final : public rpc::ftp_server::FtpServerService::Service { +public: + FtpServerServiceImpl(LazyServerPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} + + template + void fillResponseWithResult(ResponseType* response, mavsdk::FtpServer::Result& result) const + { + auto rpc_result = translateToRpcResult(result); + + auto* rpc_ftp_server_result = new rpc::ftp_server::FtpServerResult(); + rpc_ftp_server_result->set_result(rpc_result); + std::stringstream ss; + ss << result; + rpc_ftp_server_result->set_result_str(ss.str()); + + response->set_allocated_ftp_server_result(rpc_ftp_server_result); + } + + static rpc::ftp_server::FtpServerResult::Result + translateToRpcResult(const mavsdk::FtpServer::Result& result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case mavsdk::FtpServer::Result::Unknown: + return rpc::ftp_server::FtpServerResult_Result_RESULT_UNKNOWN; + case mavsdk::FtpServer::Result::Success: + return rpc::ftp_server::FtpServerResult_Result_RESULT_SUCCESS; + case mavsdk::FtpServer::Result::DoesNotExist: + return rpc::ftp_server::FtpServerResult_Result_RESULT_DOES_NOT_EXIST; + case mavsdk::FtpServer::Result::Busy: + return rpc::ftp_server::FtpServerResult_Result_RESULT_BUSY; + } + } + + static mavsdk::FtpServer::Result + translateFromRpcResult(const rpc::ftp_server::FtpServerResult::Result result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case rpc::ftp_server::FtpServerResult_Result_RESULT_UNKNOWN: + return mavsdk::FtpServer::Result::Unknown; + case rpc::ftp_server::FtpServerResult_Result_RESULT_SUCCESS: + return mavsdk::FtpServer::Result::Success; + case rpc::ftp_server::FtpServerResult_Result_RESULT_DOES_NOT_EXIST: + return mavsdk::FtpServer::Result::DoesNotExist; + case rpc::ftp_server::FtpServerResult_Result_RESULT_BUSY: + return mavsdk::FtpServer::Result::Busy; + } + } + + grpc::Status SetRootDir( + grpc::ServerContext* /* context */, + const rpc::ftp_server::SetRootDirRequest* request, + rpc::ftp_server::SetRootDirResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::FtpServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "SetRootDir sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->set_root_dir(request->path()); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + void stop() + { + _stopped.store(true); + for (auto& prom : _stream_stop_promises) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } + } + +private: + void register_stream_stop_promise(std::weak_ptr> prom) + { + // If we have already stopped, set promise immediately and don't add it to list. + if (_stopped.load()) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } else { + _stream_stop_promises.push_back(prom); + } + } + + void unregister_stream_stop_promise(std::shared_ptr> prom) + { + for (auto it = _stream_stop_promises.begin(); it != _stream_stop_promises.end(); + /* ++it */) { + if (it->lock() == prom) { + it = _stream_stop_promises.erase(it); + } else { + ++it; + } + } + } + + LazyServerPlugin& _lazy_plugin; + + std::atomic _stopped{false}; + std::vector>> _stream_stop_promises{}; +}; + +} // namespace mavsdk_server +} // namespace mavsdk \ No newline at end of file diff --git a/src/plugins.txt b/src/plugins.txt index a948879239..704c0fec55 100644 --- a/src/plugins.txt +++ b/src/plugins.txt @@ -8,6 +8,7 @@ component_information_server failure follow_me ftp +ftp_server geofence gimbal gripper diff --git a/src/system_tests/CMakeLists.txt b/src/system_tests/CMakeLists.txt index 2a5292bc29..068087c940 100644 --- a/src/system_tests/CMakeLists.txt +++ b/src/system_tests/CMakeLists.txt @@ -1,5 +1,4 @@ add_executable(system_tests_runner - ../mavsdk/core/unittests_main.cpp camera_take_photo.cpp component_information.cpp action_arm_disarm.cpp @@ -9,6 +8,17 @@ add_executable(system_tests_runner param_get_all.cpp mission_raw_upload.cpp telemetry_subscription.cpp + fs_helpers.cpp + ftp_download_file.cpp + ftp_download_file_burst.cpp + ftp_remove_file.cpp + ftp_upload_file.cpp + ftp_rename_file.cpp + ftp_create_dir.cpp + ftp_remove_dir.cpp + ftp_compare_files.cpp + ftp_list_dir.cpp + system_tests_runner.cpp ) target_include_directories(system_tests_runner @@ -23,3 +33,15 @@ target_link_libraries(system_tests_runner gtest_main gmock ) + +if(ENABLE_CPPTRACE) + find_package(cpptrace REQUIRED) + target_link_libraries(system_tests_runner + PRIVATE + cpptrace::cpptrace + ) + target_compile_definitions(system_tests_runner + PRIVATE + -DENABLE_CPPTRACE + ) +endif() diff --git a/src/system_tests/fs_helpers.cpp b/src/system_tests/fs_helpers.cpp new file mode 100644 index 0000000000..88c538b14a --- /dev/null +++ b/src/system_tests/fs_helpers.cpp @@ -0,0 +1,64 @@ +#include "fs_helpers.h" +#include +#include +#include +#include +#include +#include + +bool create_temp_file(const fs::path& path, size_t len, uint8_t start) +{ + const auto parent_path = path.parent_path(); + create_directories(parent_path); + + std::ofstream tempfile{}; + tempfile.open(path, std::ios::out | std::ios::binary | std::ios::trunc); + if (tempfile.fail()) { + std::cout << "Failed to open temp file."; + return false; + } + + for (size_t i = 0; i < len; ++i) { + const char c = (i + start) % 256; + tempfile.write(&c, 1); + } + + tempfile.close(); + + return true; +} + +bool reset_directories(const fs::path& path) +{ + std::error_code ec; + fs::remove_all(path, ec); + + return fs::create_directories(path); +} + +bool are_files_identical(const fs::path& path1, const fs::path& path2) +{ + std::ifstream file1(path1, std::ios::binary); + std::ifstream file2(path2, std::ios::binary); + + if (!file1) { + std::cout << "Could not open " << path1 << std::endl; + return false; + } + + if (!file2) { + std::cout << "Could not open " << path2 << std::endl; + return false; + } + + std::istreambuf_iterator begin1(file1); + std::istreambuf_iterator begin2(file2); + std::istreambuf_iterator end; + + return std::equal(begin1, end, begin2, end); +} + +bool file_exists(const fs::path& path) +{ + return fs::exists(path); +} diff --git a/src/system_tests/fs_helpers.h b/src/system_tests/fs_helpers.h new file mode 100644 index 0000000000..54f194a5ed --- /dev/null +++ b/src/system_tests/fs_helpers.h @@ -0,0 +1,14 @@ +#pragma once + +#include +#include + +namespace fs = std::filesystem; + +bool create_temp_file(const fs::path& path, size_t len, uint8_t start = 0); + +bool reset_directories(const fs::path& path); + +bool are_files_identical(const fs::path& path1, const fs::path& path2); + +bool file_exists(const fs::path& path); diff --git a/src/system_tests/ftp_compare_files.cpp b/src/system_tests/ftp_compare_files.cpp new file mode 100644 index 0000000000..db4815ff66 --- /dev/null +++ b/src/system_tests/ftp_compare_files.cpp @@ -0,0 +1,76 @@ +#include "log.h" +#include "mavsdk.h" +#include +#include +#include +#include +#include +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; + +static const fs::path temp_file = "data.bin"; +static const fs::path temp_file_same = "data_copy.bin"; +static const fs::path temp_file_different = "rhubarb.bin"; + +TEST(SystemTest, FtpCompareFiles) +{ + ASSERT_TRUE(reset_directories(temp_dir_provided)); + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 1000)); + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file_same, 1000)); + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file_different, 1000, 42)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // First we try to compare the file without the root directory set. + // We expect an error as we don't have any permission. + // + auto result = ftp.are_files_identical( + (temp_dir_provided / temp_file).string(), (temp_file_same).string()); + EXPECT_EQ(result.first, Ftp::Result::ProtocolError); + EXPECT_EQ(result.second, false); + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + result = + ftp.are_files_identical((temp_dir_provided / temp_file).string(), temp_file_same.string()); + EXPECT_EQ(result.first, Ftp::Result::Success); + EXPECT_EQ(result.second, true); + + result = ftp.are_files_identical( + (temp_dir_provided / temp_file).string(), temp_file_different.string()); + EXPECT_EQ(result.first, Ftp::Result::Success); + EXPECT_EQ(result.second, false); +} diff --git a/src/system_tests/ftp_create_dir.cpp b/src/system_tests/ftp_create_dir.cpp new file mode 100644 index 0000000000..cf15c8bcc5 --- /dev/null +++ b/src/system_tests/ftp_create_dir.cpp @@ -0,0 +1,60 @@ +#include "log.h" +#include "mavsdk.h" +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +#include +#include +#include + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; + +static const fs::path temp_dir = "folder"; + +TEST(SystemTest, FtpCreateDir) +{ + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + auto ftp = Ftp{system}; + + // First we try to create a folder without the root directory set. + // We expect an error as we don't have any permission. + EXPECT_EQ(ftp.create_directory(temp_dir.string()), Ftp::Result::ProtocolError); + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + EXPECT_EQ(ftp.create_directory(temp_dir.string()), Ftp::Result::Success); + + EXPECT_TRUE(file_exists(temp_dir_provided / temp_dir)); +} diff --git a/src/system_tests/ftp_download_file.cpp b/src/system_tests/ftp_download_file.cpp new file mode 100644 index 0000000000..ea7d2341c5 --- /dev/null +++ b/src/system_tests/ftp_download_file.cpp @@ -0,0 +1,355 @@ +#include "log.h" +#include "mavsdk.h" +#include +#include +#include +#include +#include +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; +static const fs::path temp_dir_downloaded = "/tmp/mavsdk_systemtest_temp_data/downloaded"; + +static const fs::path temp_file = "data.bin"; + +TEST(SystemTest, FtpDownloadFile) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // First we try to access the file without the root directory set. + // We expect that an error as we don't have any permission. + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + temp_file.string(), + temp_dir_downloaded.string(), + false, + [&prom](Ftp::Result result, Ftp::ProgressData) { prom.set_value(result); }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); + } + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + temp_file.string(), + temp_dir_downloaded.string(), + false, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); + } +} + +TEST(SystemTest, FtpDownloadBigFile) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50000)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + temp_file.string(), + temp_dir_downloaded.string(), + false, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(20)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); +} + +TEST(SystemTest, FtpDownloadBigFileLossy) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 10000)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + unsigned counter = 0; + auto drop_some = [&counter](mavlink_message_t&) { return counter++ % 5; }; + + mavsdk_groundstation.intercept_incoming_messages_async(drop_some); + mavsdk_groundstation.intercept_outgoing_messages_async(drop_some); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + ("" / temp_file).string(), + temp_dir_downloaded.string(), + false, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(20)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); + + // Before going out of scope, we need to make sure to no longer access the + // drop_some callback which accesses the local counter variable. + mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); +} + +TEST(SystemTest, FtpDownloadStopAndTryAgain) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 1000)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + // Once we received half, we want to stop all traffic. + bool got_half = false; + auto drop_at_some_point = [&got_half](mavlink_message_t&) { return !got_half; }; + + mavsdk_groundstation.intercept_incoming_messages_async(drop_at_some_point); + mavsdk_groundstation.intercept_outgoing_messages_async(drop_at_some_point); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + ("" / temp_file).string(), + temp_dir_downloaded.string(), + false, + [&prom, &got_half](Ftp::Result result, Ftp::ProgressData progress_data) { + if (progress_data.bytes_transferred > 500) { + got_half = true; + } + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Timeout); + + // Before going out of scope, we need to make sure to no longer access the + // drop_some callback which accesses the local counter variable. + mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); + + { + // Now try again + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + ("" / temp_file).string(), + temp_dir_downloaded.string(), + false, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + } +} + +TEST(SystemTest, FtpDownloadFileOutsideOfRoot) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + (fs::path("") / ".." / temp_file).string(), + temp_dir_downloaded.string(), + false, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + prom.set_value(result); + }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); + } +} diff --git a/src/system_tests/ftp_download_file_burst.cpp b/src/system_tests/ftp_download_file_burst.cpp new file mode 100644 index 0000000000..1269b4e4fd --- /dev/null +++ b/src/system_tests/ftp_download_file_burst.cpp @@ -0,0 +1,355 @@ +#include "log.h" +#include "mavsdk.h" +#include +#include +#include +#include +#include +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; +static const fs::path temp_dir_downloaded = "/tmp/mavsdk_systemtest_temp_data/downloaded"; + +static const fs::path temp_file = "data.bin"; + +TEST(SystemTest, FtpDownloadBurstFile) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // First we try to access the file without the root directory set. + // We expect that an error as we don't have any permission. + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + temp_file.string(), + temp_dir_downloaded.string(), + true, + [&prom](Ftp::Result result, Ftp::ProgressData) { prom.set_value(result); }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); + } + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + temp_file.string(), + temp_dir_downloaded.string(), + true, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); + } +} + +TEST(SystemTest, FtpDownloadBurstBigFile) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50000)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + temp_file.string(), + temp_dir_downloaded.string(), + true, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(20)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); +} + +TEST(SystemTest, FtpDownloadBurstBigFileLossy) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 10000)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + unsigned counter = 0; + auto drop_some = [&counter](mavlink_message_t&) { return counter++ % 5; }; + + mavsdk_groundstation.intercept_incoming_messages_async(drop_some); + mavsdk_groundstation.intercept_outgoing_messages_async(drop_some); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + ("" / temp_file).string(), + temp_dir_downloaded.string(), + true, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(20)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); + + // Before going out of scope, we need to make sure to no longer access the + // drop_some callback which accesses the local counter variable. + mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); +} + +TEST(SystemTest, FtpDownloadBurstStopAndTryAgain) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 1000)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + // Once we received half, we want to stop all traffic. + bool got_half = false; + auto drop_at_some_point = [&got_half](mavlink_message_t&) { return !got_half; }; + + mavsdk_groundstation.intercept_incoming_messages_async(drop_at_some_point); + mavsdk_groundstation.intercept_outgoing_messages_async(drop_at_some_point); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + ("" / temp_file).string(), + temp_dir_downloaded.string(), + true, + [&prom, &got_half](Ftp::Result result, Ftp::ProgressData progress_data) { + if (progress_data.bytes_transferred > 500) { + got_half = true; + } + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Timeout); + + // Before going out of scope, we need to make sure to no longer access the + // drop_some callback which accesses the local counter variable. + mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); + + { + // Now try again + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + ("" / temp_file).string(), + temp_dir_downloaded.string(), + true, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + } +} + +TEST(SystemTest, FtpDownloadBurstFileOutsideOfRoot) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); + ASSERT_TRUE(reset_directories(temp_dir_downloaded)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.download_async( + (fs::path("") / ".." / temp_file).string(), + temp_dir_downloaded.string(), + true, + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + prom.set_value(result); + }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); + } +} diff --git a/src/system_tests/ftp_list_dir.cpp b/src/system_tests/ftp_list_dir.cpp new file mode 100644 index 0000000000..38683fab01 --- /dev/null +++ b/src/system_tests/ftp_list_dir.cpp @@ -0,0 +1,76 @@ +#include "log.h" +#include "mavsdk.h" +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +#include +#include +#include +#include + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; + +static const std::string temp_dir = "folder"; +static const std::string temp_file = "file"; + +TEST(SystemTest, FtpListDir) +{ + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + std::vector truth_list; + + for (unsigned i = 0; i < 100; ++i) { + auto foldername = std::string(temp_dir + std::to_string(i)); + auto filename = std::string(temp_file + std::to_string(i)); + ASSERT_TRUE(reset_directories(temp_dir_provided / fs::path(foldername))); + ASSERT_TRUE(create_temp_file(temp_dir_provided / fs::path(filename), i)); + + truth_list.push_back(std::string("D") + foldername); + truth_list.push_back(std::string("F") + filename + std::string("\t") + std::to_string(i)); + } + + std::sort(truth_list.begin(), truth_list.end()); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + auto ftp = Ftp{system}; + + // First we try to list a folder without the root directory set. + // We expect an error as we don't have any permission. + EXPECT_EQ(ftp.list_directory("./").first, Ftp::Result::ProtocolError); + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto ret = ftp.list_directory("./"); + EXPECT_EQ(ret.first, Ftp::Result::Success); + + EXPECT_EQ(ret.second, truth_list); +} diff --git a/src/system_tests/ftp_remove_dir.cpp b/src/system_tests/ftp_remove_dir.cpp new file mode 100644 index 0000000000..4aae10a351 --- /dev/null +++ b/src/system_tests/ftp_remove_dir.cpp @@ -0,0 +1,100 @@ +#include "log.h" +#include "mavsdk.h" +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +#include +#include +#include + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; + +static const fs::path temp_dir = "folder"; +static const fs::path temp_file = "file.bin"; + +TEST(SystemTest, FtpRemoveDir) +{ + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + ASSERT_TRUE(reset_directories(temp_dir_provided / temp_dir)); + + auto ftp = Ftp{system}; + + // First we try to create a folder without the root directory set. + // We expect an error as we don't have any permission. + EXPECT_EQ(ftp.create_directory(temp_dir.string()), Ftp::Result::ProtocolError); + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + EXPECT_EQ(ftp.remove_directory(temp_dir.string()), Ftp::Result::Success); + + EXPECT_FALSE(file_exists(temp_dir_provided / temp_dir)); +} + +TEST(SystemTest, FtpRemoveDirNotEmpty) +{ + ASSERT_TRUE(reset_directories(temp_dir_provided / temp_dir)); + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_dir / temp_file, 100)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + // TODO: not sure if this is the correct error for "dir not empty" + EXPECT_EQ(ftp.remove_directory(temp_dir.string()), Ftp::Result::ProtocolError); + + EXPECT_TRUE(file_exists(temp_dir_provided / temp_dir)); +} diff --git a/src/system_tests/ftp_remove_file.cpp b/src/system_tests/ftp_remove_file.cpp new file mode 100644 index 0000000000..944fa8439b --- /dev/null +++ b/src/system_tests/ftp_remove_file.cpp @@ -0,0 +1,133 @@ +#include "log.h" +#include "mavsdk.h" +#include +#include +#include +#include +#include +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; + +static const fs::path temp_file = "data.bin"; + +TEST(SystemTest, FtpRemoveFile) +{ + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // First we try to remove the file without the root directory set. + // We expect an error as we don't have any permission. + EXPECT_EQ(ftp.remove_file(temp_file.string()), Ftp::Result::ProtocolError); + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + EXPECT_EQ(ftp.remove_file(temp_file.string()), Ftp::Result::Success); + + EXPECT_FALSE(file_exists(temp_dir_provided / temp_file)); +} + +TEST(SystemTest, FtpRemoveFileThatDoesNotExist) +{ + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + // Don't create the file, empty the directory instead. + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + auto ftp = Ftp{system}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + EXPECT_EQ(ftp.remove_file(temp_file.string()), Ftp::Result::FileDoesNotExist); + + EXPECT_FALSE(file_exists(temp_dir_provided / temp_file)); +} + +TEST(SystemTest, FtpRemoveFileOutsideOfRoot) +{ + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + // Don't create the file, empty the directory instead. + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + auto ftp = Ftp{system}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + EXPECT_EQ(ftp.remove_file((fs::path("..") / temp_file).string()), Ftp::Result::ProtocolError); +} diff --git a/src/system_tests/ftp_rename_file.cpp b/src/system_tests/ftp_rename_file.cpp new file mode 100644 index 0000000000..87a62813de --- /dev/null +++ b/src/system_tests/ftp_rename_file.cpp @@ -0,0 +1,64 @@ +#include "log.h" +#include "mavsdk.h" +#include +#include +#include +#include +#include +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; + +static const fs::path temp_file = "data.bin"; +static const fs::path temp_file_renamed = "rhubarb.bin"; + +TEST(SystemTest, FtpRenameFile) +{ + ASSERT_TRUE(reset_directories(temp_dir_provided)); + ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // First we try to rename the file without the root directory set. + // We expect an error as we don't have any permission. + EXPECT_EQ( + ftp.rename(temp_file.string(), temp_file_renamed.string()), Ftp::Result::ProtocolError); + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + EXPECT_EQ(ftp.rename(temp_file.string(), temp_file_renamed.string()), Ftp::Result::Success); + + EXPECT_TRUE(file_exists(temp_dir_provided / temp_file_renamed)); +} diff --git a/src/system_tests/ftp_upload_file.cpp b/src/system_tests/ftp_upload_file.cpp new file mode 100644 index 0000000000..04f9e1ed63 --- /dev/null +++ b/src/system_tests/ftp_upload_file.cpp @@ -0,0 +1,357 @@ +#include "log.h" +#include "mavsdk.h" +#include +#include +#include +#include +#include +#include "plugins/ftp/ftp.h" +#include "plugins/ftp_server/ftp_server.h" +#include "fs_helpers.h" + +using namespace mavsdk; + +static constexpr double reduced_timeout_s = 0.1; + +// TODO: make this compatible for Windows using GetTempPath2 + +namespace fs = std::filesystem; + +static auto sep = fs::path::preferred_separator; + +static const fs::path temp_dir_provided = "/tmp/mavsdk_systemtest_temp_data/provided"; +static const fs::path temp_dir_to_upload = "/tmp/mavsdk_systemtest_temp_data/to_upload"; + +static const fs::path temp_file = "data.bin"; + +TEST(SystemTest, FtpUploadFile) +{ + ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 50)); + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // First we try to access the file without the root directory set. + // We expect an error as we don't have any permission. + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.upload_async( + (temp_dir_to_upload / temp_file).string(), + ".", + [&prom](Ftp::Result result, Ftp::ProgressData) { prom.set_value(result); }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); + } + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.upload_async( + (temp_dir_to_upload / temp_file).string(), + ".", + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Upload progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_to_upload / temp_file, temp_dir_provided / temp_file)); + } +} + +TEST(SystemTest, FtpUploadBigFile) +{ + ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 10000)); + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.upload_async( + (temp_dir_to_upload / temp_file).string(), + "", + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Upload progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_to_upload / temp_file, temp_dir_provided / temp_file)); + } +} + +TEST(SystemTest, FtpUploadBigFileLossy) +{ + ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 10000)); + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + unsigned counter = 0; + auto drop_some = [&counter](mavlink_message_t&) { return counter++ % 5; }; + + mavsdk_groundstation.intercept_incoming_messages_async(drop_some); + mavsdk_groundstation.intercept_outgoing_messages_async(drop_some); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.upload_async( + (temp_dir_to_upload / temp_file).string(), + "./", + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Upload progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + + EXPECT_TRUE( + are_files_identical(temp_dir_to_upload / temp_file, temp_dir_provided / temp_file)); + } + + mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); +} + +TEST(SystemTest, FtpUploadStopAndTryAgain) +{ + ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 1000)); + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + // Once we received half, we want to stop all traffic. + bool got_half = false; + auto drop_at_some_point = [&got_half](mavlink_message_t&) { return !got_half; }; + + mavsdk_groundstation.intercept_incoming_messages_async(drop_at_some_point); + mavsdk_groundstation.intercept_outgoing_messages_async(drop_at_some_point); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + ftp_server.set_root_dir(temp_dir_provided.string()); + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.upload_async( + (temp_dir_to_upload / temp_file).string(), + "", + [&prom, &got_half](Ftp::Result result, Ftp::ProgressData progress_data) { + if (progress_data.bytes_transferred > 500) { + got_half = true; + } + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Timeout); + + // Before going out of scope, we need to make sure to no longer access the + // drop_some callback which accesses the local counter variable. + mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); + + { + // Now try again + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.upload_async( + (temp_dir_to_upload / temp_file).string(), + "", + [&prom, &got_half](Ftp::Result result, Ftp::ProgressData progress_data) { + if (result != Ftp::Result::Next) { + prom.set_value(result); + } else { + LogDebug() << "Download progress: " << progress_data.bytes_transferred << "/" + << progress_data.total_bytes << " bytes"; + } + }); + + auto future_status = fut.wait_for(std::chrono::seconds(10)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::Success); + } +} + +TEST(SystemTest, FtpUploadFileOutsideOfRoot) +{ + ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 50)); + ASSERT_TRUE(reset_directories(temp_dir_provided)); + + // A test trying to push something into the parent (../) directory which + // shouldn't be allowed! + + Mavsdk mavsdk_groundstation; + mavsdk_groundstation.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + mavsdk_groundstation.set_timeout_s(reduced_timeout_s); + + Mavsdk mavsdk_autopilot; + mavsdk_autopilot.set_configuration( + Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_timeout_s(reduced_timeout_s); + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ( + mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{ + mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); + ASSERT_TRUE(maybe_system); + auto system = maybe_system.value(); + + ASSERT_TRUE(system->has_autopilot()); + + auto ftp = Ftp{system}; + + // Now we set the root dir and expect it to work. + ftp_server.set_root_dir(temp_dir_provided.string()); + + { + auto prom = std::promise(); + auto fut = prom.get_future(); + ftp.upload_async( + (temp_dir_to_upload / temp_file).string(), + "../", + [&prom](Ftp::Result result, Ftp::ProgressData progress_data) { + prom.set_value(result); + }); + + auto future_status = fut.wait_for(std::chrono::seconds(1)); + ASSERT_EQ(future_status, std::future_status::ready); + EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); + } +} diff --git a/src/system_tests/param_get_all.cpp b/src/system_tests/param_get_all.cpp index 8cee40950c..1680f2290c 100644 --- a/src/system_tests/param_get_all.cpp +++ b/src/system_tests/param_get_all.cpp @@ -134,7 +134,7 @@ TEST(SystemTest, ParamGetAllLossy) auto drop_some = [&counter](mavlink_message_t&) { return counter++ % 5; }; mavsdk_groundstation.intercept_incoming_messages_async(drop_some); - mavsdk_groundstation.intercept_incoming_messages_async(drop_some); + mavsdk_groundstation.intercept_outgoing_messages_async(drop_some); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( @@ -186,5 +186,5 @@ TEST(SystemTest, ParamGetAllLossy) // Before going out of scope, we need to make sure to no longer access the // drop_some callback which accesses the local counter variable. mavsdk_groundstation.intercept_incoming_messages_async(nullptr); - mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); } diff --git a/src/system_tests/system_tests_runner.cpp b/src/system_tests/system_tests_runner.cpp new file mode 100644 index 0000000000..2e770f80ae --- /dev/null +++ b/src/system_tests/system_tests_runner.cpp @@ -0,0 +1,32 @@ +#if defined(ENABLE_CPPTRACE) +#include +#include +#include "log.h" +#include +#endif +#include + +#if defined(ENABLE_CPPTRACE) +void handler(int sig) +{ + mavsdk::LogErr() << "Got signal: " << strsignal(sig) << " (" << sig << ")"; + cpptrace::print_trace(); + exit(1); +} +#endif + +int main(int argc, char** argv) +{ +#if defined(ENABLE_CPPTRACE) + signal(SIGSEGV, handler); + signal(SIGQUIT, handler); + signal(SIGABRT, handler); + signal(SIGILL, handler); + signal(SIGBUS, handler); + signal(SIGPIPE, handler); + signal(SIGFPE, handler); +#endif + + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/src/third_party/gtest b/src/third_party/gtest index 4580469122..f8d7d77c06 160000 --- a/src/third_party/gtest +++ b/src/third_party/gtest @@ -1 +1 @@ -Subproject commit 45804691223635953f311cf31a10c632553bbfc3 +Subproject commit f8d7d77c06936315286eb55f8de22cd23c188571 diff --git a/third_party/CMakeLists.txt b/third_party/CMakeLists.txt index f56d429ccb..647a866a00 100644 --- a/third_party/CMakeLists.txt +++ b/third_party/CMakeLists.txt @@ -26,5 +26,11 @@ if (SUPERBUILD) build_target(re2) build_target(grpc) endif() + endif() +if (ENABLE_CPPTRACE) + list(APPEND CMAKE_PREFIX_PATH "${DEPS_INSTALL_PATH}") + set(CMAKE_PREFIX_PATH ${CMAKE_PREFIX_PATH} PARENT_SCOPE) + build_target(cpptrace) +endif() diff --git a/third_party/cpptrace/CMakeLists.txt b/third_party/cpptrace/CMakeLists.txt new file mode 100644 index 0000000000..63b63ca8a3 --- /dev/null +++ b/third_party/cpptrace/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.1) + +project(external-cpptrace) +include(ExternalProject) + +list(APPEND CMAKE_ARGS + "-DCMAKE_PREFIX_PATH:PATH=${CMAKE_PREFIX_PATH}" + "-DCMAKE_INSTALL_PREFIX:PATH=${CMAKE_INSTALL_PREFIX}" + "-DCMAKE_TOOLCHAIN_FILE:PATH=${CMAKE_TOOLCHAIN_FILE}" + "-DCMAKE_POSITION_INDEPENDENT_CODE=ON" + "-DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}" + "-DCMAKE_CXX_STANDARD=17" + ) + +message(STATUS "Preparing external project \"cpptrace\" with args:") +foreach(CMAKE_ARG ${CMAKE_ARGS}) + message(STATUS "-- ${CMAKE_ARG}") +endforeach() + +ExternalProject_add( + cpptrace + GIT_REPOSITORY https://github.com/jeremy-rifkin/cpptrace.git + GIT_TAG 4b11b87e4d905d003d0325a53994441cc767017a + PREFIX cpptrace + CMAKE_ARGS "${CMAKE_ARGS}" + ) diff --git a/tools/run-docker.sh b/tools/run-docker.sh index 7096a91359..f2873a3ee8 100755 --- a/tools/run-docker.sh +++ b/tools/run-docker.sh @@ -1,6 +1,6 @@ #!/usr/bin/env sh -dockerimage=mavsdk/mavsdk-ubuntu-22.04-px4-sitl-v1.13 +dockerimage=docker.io/mavsdk/mavsdk-ubuntu-22.04-px4-sitl-v1.13 if type podman > /dev/null 2> /dev/null then