diff --git a/proto b/proto index 815469718f..186d7f2032 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 815469718fdb0ad02664b840e555db086ef438ca +Subproject commit 186d7f2032abed217137bd75194eb996067315d4 diff --git a/src/mavsdk/core/fs.cpp b/src/mavsdk/core/fs.cpp index 96c02bd830..4f8ecc98e2 100644 --- a/src/mavsdk/core/fs.cpp +++ b/src/mavsdk/core/fs.cpp @@ -17,6 +17,7 @@ #include "fs.h" #include "filesystem_include.h" #include "log.h" +#include "unused.h" #ifndef PATH_MAX #define PATH_MAX 4096 @@ -26,10 +27,9 @@ namespace mavsdk { -bool fs_exists(const std::string& filename) +bool fs_exists(const fs::path& path) { - struct stat buffer; - return (stat(filename.c_str(), &buffer) == 0); + return fs::exists(path); } uint32_t fs_file_size(const std::string& filename) @@ -115,10 +115,11 @@ 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) +bool fs_remove(const fs::path& path) { - LogWarn() << "Removing file: " << path; - return (remove(path.c_str()) == 0); + std::error_code ec; + return fs::remove(path, ec); + UNUSED(ec); } bool fs_rename(const std::string& old_name, const std::string& new_name) diff --git a/src/mavsdk/core/fs.h b/src/mavsdk/core/fs.h index 3ceafbc7df..5559f89d6c 100644 --- a/src/mavsdk/core/fs.h +++ b/src/mavsdk/core/fs.h @@ -3,6 +3,9 @@ #include #include #include +#include + +namespace fs = std::filesystem; namespace mavsdk { @@ -12,7 +15,7 @@ const std::string path_separator = "\\"; const std::string path_separator = "/"; #endif -bool fs_exists(const std::string& filename); +bool fs_exists(const fs::path& filename); uint32_t fs_file_size(const std::string& filename); @@ -22,10 +25,10 @@ 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_remove(const fs::path& 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 +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_ftp_server.cpp b/src/mavsdk/core/mavlink_ftp_server.cpp index daa88d03c9..84da83be2c 100644 --- a/src/mavsdk/core/mavlink_ftp_server.cpp +++ b/src/mavsdk/core/mavlink_ftp_server.cpp @@ -16,6 +16,7 @@ #define O_ACCMODE (O_RDONLY | O_WRONLY | O_RDWR) #endif +#include "unused.h" #include "crc32.h" #include "fs.h" #include @@ -26,6 +27,13 @@ namespace mavsdk { 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); }, @@ -38,8 +46,11 @@ void MavlinkFtpServer::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); - LogWarn() << "target: " << std::to_string(ftp_req.target_component) - << ", our: " << std::to_string(_server_component_impl.get_own_component_id()); + 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()) { @@ -57,22 +68,14 @@ void MavlinkFtpServer::process_mavlink_ftp_message(const mavlink_message_t& msg) ServerResult error_code = ServerResult::SUCCESS; - // basic sanity checks; must validate length before use + // Basic sanity check: 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"; - // _server_component_impl.send_message(_last_reply); - // return; - // } - //} + if (_debugging) { + LogDebug() << "FTP opcode: " << (int)payload->opcode << ", size: " << (int)payload->size + << ", offset: " << (int)payload->offset << ", seq: " << payload->seq_number; + } if (_curr_op != CMD_NONE && _curr_op != payload->req_opcode) { LogWarn() << "Received ACK not matching our current operation, resetting"; @@ -84,77 +87,107 @@ void MavlinkFtpServer::process_mavlink_ftp_message(const mavlink_message_t& msg) switch (payload->opcode) { case CMD_NONE: - LogInfo() << "OPC:CMD_NONE"; + if (_debugging) { + LogDebug() << "OPC:CMD_NONE"; + } break; case CMD_TERMINATE_SESSION: - LogInfo() << "OPC:CMD_TERMINATE_SESSION"; + if (_debugging) { + LogDebug() << "OPC:CMD_TERMINATE_SESSION"; + } error_code = _work_terminate(payload); break; case CMD_RESET_SESSIONS: - LogInfo() << "OPC:CMD_RESET_SESSIONS"; + if (_debugging) { + LogDebug() << "OPC:CMD_RESET_SESSIONS"; + } error_code = _work_reset(payload); break; case CMD_LIST_DIRECTORY: - LogInfo() << "OPC:CMD_LIST_DIRECTORY"; + if (_debugging) { + LogDebug() << "OPC:CMD_LIST_DIRECTORY"; + } error_code = _work_list(payload); break; case CMD_OPEN_FILE_RO: - LogInfo() << "OPC:CMD_OPEN_FILE_RO"; + if (_debugging) { + LogDebug() << "OPC:CMD_OPEN_FILE_RO"; + } error_code = _work_open(payload, O_RDONLY); break; case CMD_CREATE_FILE: - LogInfo() << "OPC:CMD_CREATE_FILE"; + if (_debugging) { + LogDebug() << "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"; + if (_debugging) { + LogDebug() << "OPC:CMD_OPEN_FILE_WO"; + } error_code = _work_open(payload, O_CREAT | O_WRONLY); break; case CMD_READ_FILE: - LogInfo() << "OPC:CMD_READ_FILE"; + if (_debugging) { + LogDebug() << "OPC:CMD_READ_FILE"; + } error_code = _work_read(payload); break; case CMD_BURST_READ_FILE: - LogInfo() << "OPC:CMD_BURST_READ_FILE"; + if (_debugging) { + LogDebug() << "OPC:CMD_BURST_READ_FILE"; + } error_code = _work_burst(payload); stream_send = true; break; case CMD_WRITE_FILE: - LogInfo() << "OPC:CMD_WRITE_FILE"; + if (_debugging) { + LogDebug() << "OPC:CMD_WRITE_FILE"; + } error_code = _work_write(payload); break; case CMD_REMOVE_FILE: - LogInfo() << "OPC:CMD_REMOVE_FILE"; + if (_debugging) { + LogDebug() << "OPC:CMD_REMOVE_FILE"; + } error_code = _work_remove_file(payload); break; case CMD_RENAME: - LogInfo() << "OPC:CMD_RENAME"; + if (_debugging) { + LogDebug() << "OPC:CMD_RENAME"; + } error_code = _work_rename(payload); break; case CMD_CREATE_DIRECTORY: - LogInfo() << "OPC:CMD_CREATE_DIRECTORY"; + if (_debugging) { + LogDebug() << "OPC:CMD_CREATE_DIRECTORY"; + } error_code = _work_create_directory(payload); break; case CMD_REMOVE_DIRECTORY: - LogInfo() << "OPC:CMD_REMOVE_DIRECTORY"; + if (_debugging) { + LogDebug() << "OPC:CMD_REMOVE_DIRECTORY"; + } error_code = _work_remove_directory(payload); break; case CMD_CALC_FILE_CRC32: - LogInfo() << "OPC:CMD_CALC_FILE_CRC32"; + if (_debugging) { + LogDebug() << "OPC:CMD_CALC_FILE_CRC32"; + } error_code = _work_calc_file_CRC32(payload); break; @@ -164,7 +197,9 @@ void MavlinkFtpServer::process_mavlink_ftp_message(const mavlink_message_t& msg) } } - LogWarn() << "Error code: " << std::to_string(error_code); + if (_debugging) { + LogDebug() << "Error code: " << std::to_string(error_code); + } payload->seq_number++; @@ -174,7 +209,6 @@ void MavlinkFtpServer::process_mavlink_ftp_message(const mavlink_message_t& msg) payload->opcode = RSP_ACK; } else { - LogWarn() << "This case!"; uint8_t r_errno = errno; payload->req_opcode = payload->opcode; payload->opcode = RSP_NAK; @@ -203,10 +237,6 @@ void MavlinkFtpServer::process_mavlink_ftp_message(const mavlink_message_t& msg) _last_reply_valid = true; _last_reply_seq = payload->seq_number; - if (payload->opcode == RSP_NAK) { - LogWarn() << "Sending nak!"; - } - mavlink_msg_file_transfer_protocol_pack( _server_component_impl.get_own_system_id(), _server_component_impl.get_own_component_id(), @@ -224,126 +254,6 @@ MavlinkFtpServer::~MavlinkFtpServer() _reset(); } -void MavlinkFtpServer::_call_op_result_callback(ServerResult result) -{ - if (_curr_op_result_callback) { - const auto temp_callback = _curr_op_result_callback; - _server_component_impl.call_user_callback( - [temp_callback, result]() { temp_callback(_translate(result)); }); - } -} - -void MavlinkFtpServer::_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; - _server_component_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 MavlinkFtpServer::_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; - _server_component_impl.call_user_callback( - [temp_callback, result, list]() { temp_callback(_translate(result), list); }); - } -} - -void MavlinkFtpServer::_call_crc32_result_callback(ServerResult result, uint32_t crc32) -{ - if (_current_crc32_result_callback) { - const auto temp_callback = _current_crc32_result_callback; - _server_component_impl.call_user_callback( - [temp_callback, result, crc32]() { temp_callback(_translate(result), crc32); }); - } -} - -MavlinkFtpServer::ClientResult MavlinkFtpServer::_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 MavlinkFtpServer::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 MavlinkFtpServer::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 MavlinkFtpServer::_end_read_session(bool delete_file) { _curr_op = CMD_NONE; @@ -375,45 +285,6 @@ void MavlinkFtpServer::_read() _send_mavlink_ftp_message(payload); } -void MavlinkFtpServer::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 MavlinkFtpServer::_end_write_session() { _curr_op = CMD_NONE; @@ -423,30 +294,6 @@ void MavlinkFtpServer::_end_write_session() _terminate_session(); } -void MavlinkFtpServer::_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 MavlinkFtpServer::_terminate_session() { if (!_session_valid) { @@ -461,39 +308,6 @@ void MavlinkFtpServer::_terminate_session() _send_mavlink_ftp_message(payload); } -std::pair> -MavlinkFtpServer::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 MavlinkFtpServer::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 MavlinkFtpServer::_list_directory(uint32_t offset) { auto payload = PayloadHeader{}; @@ -510,190 +324,6 @@ void MavlinkFtpServer::_list_directory(uint32_t offset) _send_mavlink_ftp_message(payload); } -void MavlinkFtpServer::_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); -} - -MavlinkFtpServer::ClientResult MavlinkFtpServer::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 MavlinkFtpServer::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); -} - -MavlinkFtpServer::ClientResult MavlinkFtpServer::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 MavlinkFtpServer::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); -} - -MavlinkFtpServer::ClientResult MavlinkFtpServer::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 MavlinkFtpServer::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); -} - -MavlinkFtpServer::ClientResult -MavlinkFtpServer::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 MavlinkFtpServer::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 -MavlinkFtpServer::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 MavlinkFtpServer::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) { - _server_component_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) { - _server_component_impl.call_user_callback( - [temp_callback, result_remote]() { temp_callback(result_remote, false); }); - } else { - _server_component_impl.call_user_callback([temp_callback, crc_local, crc_remote]() { - temp_callback(ClientResult::Success, crc_local == crc_remote); - }); - } - }); -} - -void MavlinkFtpServer::_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 MavlinkFtpServer::_send_mavlink_ftp_message(const PayloadHeader& payload) { mavlink_msg_file_transfer_protocol_pack( @@ -728,10 +358,9 @@ std::string MavlinkFtpServer::_get_path(PayloadHeader* payload) return _get_path(_data_as_string(payload)); } -MavlinkFtpServer::ClientResult MavlinkFtpServer::set_root_directory(const std::string& root_dir) +void MavlinkFtpServer::set_root_directory(const std::string& root_dir) { _root_dir = fs_canonical(root_dir); - return ClientResult::Success; } std::string MavlinkFtpServer::_get_path(const std::string& payload_path) @@ -965,13 +594,7 @@ MavlinkFtpServer::ServerResult MavlinkFtpServer::_work_write(PayloadHeader* payl MavlinkFtpServer::ServerResult MavlinkFtpServer::_work_terminate(PayloadHeader* payload) { - if (payload->session != 0 || _session_info.fd < 0) { - _reset(); - // return ServerResult::ERR_INVALID_SESSION; - } - - payload->size = 0; - + UNUSED(payload); _reset(); return ServerResult::SUCCESS; @@ -988,10 +611,9 @@ void MavlinkFtpServer::_reset() MavlinkFtpServer::ServerResult MavlinkFtpServer::_work_reset(PayloadHeader* payload) { + UNUSED(payload); _reset(); - payload->size = 0; - return ServerResult::SUCCESS; } @@ -1083,16 +705,16 @@ MavlinkFtpServer::ServerResult MavlinkFtpServer::_work_rename(PayloadHeader* pay } } -MavlinkFtpServer::ClientResult +MavlinkFtpServer::ServerResult MavlinkFtpServer::_calc_local_file_crc32(const std::string& path, uint32_t& csum) { if (!fs_exists(path)) { - return ClientResult::FileDoesNotExist; + return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST; } int fd = ::open(path.c_str(), O_RDONLY); if (fd < 0) { - return ClientResult::FileIoError; + return ServerResult::ERR_FILE_IO_ERROR; } // Read whole file in buffer size chunks @@ -1106,7 +728,7 @@ MavlinkFtpServer::_calc_local_file_crc32(const std::string& path, uint32_t& csum int r_errno = errno; close(fd); errno = r_errno; - return ClientResult::FileIoError; + return ServerResult::ERR_FILE_IO_ERROR; } checksum.add((uint8_t*)buffer, bytes_read); @@ -1116,7 +738,7 @@ MavlinkFtpServer::_calc_local_file_crc32(const std::string& path, uint32_t& csum csum = checksum.get(); - return ClientResult::Success; + return ServerResult::SUCCESS; } MavlinkFtpServer::ServerResult MavlinkFtpServer::_work_calc_file_CRC32(PayloadHeader* payload) @@ -1133,9 +755,9 @@ MavlinkFtpServer::ServerResult MavlinkFtpServer::_work_calc_file_CRC32(PayloadHe 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; + ServerResult res = _calc_local_file_crc32(path, checksum); + if (res != ServerResult::SUCCESS) { + return res; } *reinterpret_cast(payload->data) = checksum; @@ -1198,38 +820,4 @@ MavlinkFtpServer::write_tmp_file(const std::string& path, const std::string& con } } -std::ostream& operator<<(std::ostream& str, MavlinkFtpServer::ClientResult const& result) -{ - switch (result) { - default: - // Fallthrough - case MavlinkFtpServer::ClientResult::Unknown: - return str << "Unknown"; - case MavlinkFtpServer::ClientResult::Success: - return str << "Success"; - case MavlinkFtpServer::ClientResult::Next: - return str << "Next"; - case MavlinkFtpServer::ClientResult::Timeout: - return str << "Timeout"; - case MavlinkFtpServer::ClientResult::Busy: - return str << "Busy"; - case MavlinkFtpServer::ClientResult::FileIoError: - return str << "FileIoError"; - case MavlinkFtpServer::ClientResult::FileExists: - return str << "FileExists"; - case MavlinkFtpServer::ClientResult::FileDoesNotExist: - return str << "FileDoesNotExist"; - case MavlinkFtpServer::ClientResult::FileProtected: - return str << "FileProtected"; - case MavlinkFtpServer::ClientResult::InvalidParameter: - return str << "InvalidParameter"; - case MavlinkFtpServer::ClientResult::Unsupported: - return str << "Unsupported"; - case MavlinkFtpServer::ClientResult::ProtocolError: - return str << "ProtocolError"; - case MavlinkFtpServer::ClientResult::NoSystem: - return str << "NoSystem"; - } -} - } // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_ftp_server.h b/src/mavsdk/core/mavlink_ftp_server.h index 8d5f93fe31..b1fa9474f9 100644 --- a/src/mavsdk/core/mavlink_ftp_server.h +++ b/src/mavsdk/core/mavlink_ftp_server.h @@ -29,71 +29,15 @@ class MavlinkFtpServer { explicit MavlinkFtpServer(ServerComponentImpl& server_component_impl); ~MavlinkFtpServer(); - /** - * @brief Possible results returned for FTP commands - */ - enum class ClientResult { - Unknown, /**< @brief Unknown result. */ - Success, /**< @brief Success. */ - Next, /**< @brief Intermediate message showing progress. */ - Timeout, /**< @brief Timeout. */ - Busy, /**< @brief Operation is already in progress. */ - FileIoError, /**< @brief File IO operation error. */ - FileExists, /**< @brief File exists already. */ - FileDoesNotExist, /**< @brief File does not exist. */ - FileProtected, /**< @brief File is write protected. */ - InvalidParameter, /**< @brief Invalid parameter. */ - Unsupported, /**< @brief Unsupported command. */ - ProtocolError, /**< @brief General protocol error. */ - NoSystem, /**< @brief No system connected. */ - }; - - friend std::ostream& operator<<(std::ostream& str, ClientResult const& result); - struct ProgressData { uint32_t bytes_transferred{}; /**< @brief The number of bytes already transferred. */ uint32_t total_bytes{}; /**< @brief The total bytes to transfer. */ }; - using ResultCallback = std::function; - using UploadCallback = std::function; - using DownloadCallback = std::function; - 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 reset_async(ResultCallback callback); - void download_async( - const std::string& remote_file_path, - const std::string& local_folder, - 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 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); - void - rename_async(const std::string& from_path, const std::string& to_path, ResultCallback callback); - void are_files_identical_async( - const std::string& local_path, - 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); + void set_root_directory(const std::string& root_dir); std::optional write_tmp_file(const std::string& path, const std::string& content); @@ -142,7 +86,7 @@ class MavlinkFtpServer { RSP_NAK ///< Nak response }; - using file_crc32_ResultCallback = std::function; + using file_crc32_ResultCallback = std::function; static constexpr auto DIRENT_FILE = "F"; ///< Identifies File returned from List command static constexpr auto DIRENT_DIR = "D"; ///< Identifies Directory returned from List command @@ -208,30 +152,15 @@ class MavlinkFtpServer { uint32_t _file_size = 0; std::vector _curr_directory_list{}; - 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); + ServerResult _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); @@ -273,6 +202,8 @@ class MavlinkFtpServer { std::mutex _tmp_files_mutex{}; std::unordered_map _tmp_files{}; std::string _tmp_dir{}; + + bool _debugging{false}; }; } // namespace mavsdk diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 857fe6b9e2..832d23954b 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -48,27 +48,6 @@ CameraServer::Result CameraServer::respond_take_photo( return _impl->respond_take_photo(take_photo_feedback, capture_info); } -CameraServer::StartVideoHandle -CameraServer::subscribe_start_video(const StartVideoCallback& callback) -{ - return _impl->subscribe_start_video(callback); -} - -void CameraServer::unsubscribe_start_video(StartVideoHandle handle) -{ - _impl->unsubscribe_start_video(handle); -} - -CameraServer::StopVideoHandle CameraServer::subscribe_stop_video(const StopVideoCallback& callback) -{ - return _impl->subscribe_stop_video(callback); -} - -void CameraServer::unsubscribe_stop_video(StopVideoHandle handle) -{ - _impl->unsubscribe_stop_video(handle); -} - bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 0c64edc37e..e8ee0a8d34 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -262,48 +262,6 @@ class CameraServer : public ServerPluginBase { Result respond_take_photo(TakePhotoFeedback take_photo_feedback, CaptureInfo capture_info) const; - /** - * @brief Callback type for subscribe_start_video. - */ - using StartVideoCallback = std::function; - - /** - * @brief Handle type for subscribe_start_video. - */ - using StartVideoHandle = Handle; - - /** - * @brief Subscribe to start video requests. Each request received should response to using - * StartVideoResponse - */ - StartVideoHandle subscribe_start_video(const StartVideoCallback& callback); - - /** - * @brief Unsubscribe from subscribe_start_video - */ - void unsubscribe_start_video(StartVideoHandle handle); - - /** - * @brief Callback type for subscribe_stop_video. - */ - using StopVideoCallback = std::function; - - /** - * @brief Handle type for subscribe_stop_video. - */ - using StopVideoHandle = Handle; - - /** - * @brief Subscribe to stop video requests. Each request received should response to using - * StopVideoResponse - */ - StopVideoHandle subscribe_stop_video(const StopVideoCallback& callback); - - /** - * @brief Unsubscribe from subscribe_stop_video - */ - void unsubscribe_stop_video(StopVideoHandle handle); - /** * @brief Copy constructor. */ diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index d77a8f3eb1..815dbfdb83 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -28,8 +28,6 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", - "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo", - "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -43,8 +41,6 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_SetInProgress_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeStartVideo_(CameraServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -132,38 +128,6 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhot return result; } -::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* CameraServerService::Stub::SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(channel_.get(), rpcmethod_SubscribeStartVideo_, context, request); -} - -void CameraServerService::Stub::async::SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeStartVideo_, context, request, reactor); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* CameraServerService::Stub::AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideo_, context, request, true, tag); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* CameraServerService::Stub::PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideo_, context, request, false, nullptr); -} - -::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* CameraServerService::Stub::SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), rpcmethod_SubscribeStopVideo_, context, request); -} - -void CameraServerService::Stub::async::SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeStopVideo_, context, request, reactor); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* CameraServerService::Stub::AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideo_, context, request, true, tag); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* CameraServerService::Stub::PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideo_, context, request, false, nullptr); -} - CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -205,26 +169,6 @@ CameraServerService::Service::Service() { ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* resp) { return service->RespondTakePhoto(ctx, req, resp); }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[4], - ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( - [](CameraServerService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StartVideoResponse>* writer) { - return service->SubscribeStartVideo(ctx, req, writer); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[5], - ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( - [](CameraServerService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StopVideoResponse>* writer) { - return service->SubscribeStopVideo(ctx, req, writer); - }, this))); } CameraServerService::Service::~Service() { @@ -258,20 +202,6 @@ ::grpc::Status CameraServerService::Service::RespondTakePhoto(::grpc::ServerCont return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraServerService::Service::SubscribeStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer) { - (void) context; - (void) request; - (void) writer; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - -::grpc::Status CameraServerService::Service::SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer) { - (void) context; - (void) request; - (void) writer; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index 925d9fa82d..f5bc2b5682 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -72,26 +72,6 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } - // Subscribe to start video requests. Each request received should response to using StartVideoResponse - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(SubscribeStartVideoRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> AsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(AsyncSubscribeStartVideoRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> PrepareAsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(PrepareAsyncSubscribeStartVideoRaw(context, request, cq)); - } - // Subscribe to stop video requests. Each request received should response to using StopVideoResponse - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(SubscribeStopVideoRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> AsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(AsyncSubscribeStopVideoRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); - } class async_interface { public: virtual ~async_interface() {} @@ -106,10 +86,6 @@ class CameraServerService final { // Respond to an image capture request from SubscribeTakePhoto. virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) = 0; virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Subscribe to start video requests. Each request received should response to using StartVideoResponse - virtual void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) = 0; - // Subscribe to stop video requests. Each request received should response to using StopVideoResponse - virtual void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -124,12 +100,6 @@ class CameraServerService final { virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* AsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* PrepareAsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -164,24 +134,6 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>> SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>>(SubscribeStartVideoRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>> AsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>>(AsyncSubscribeStartVideoRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>> PrepareAsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>>(PrepareAsyncSubscribeStartVideoRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(SubscribeStopVideoRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> AsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(AsyncSubscribeStopVideoRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); - } class async final : public StubInterface::async_interface { public: @@ -192,8 +144,6 @@ class CameraServerService final { void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) override; void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) override; void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) override; - void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -214,18 +164,10 @@ class CameraServerService final { ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* AsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* PrepareAsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_RespondTakePhoto_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideo_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideo_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -241,10 +183,6 @@ class CameraServerService final { virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response); - // Subscribe to start video requests. Each request received should response to using StartVideoResponse - virtual ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer); - // Subscribe to stop video requests. Each request received should response to using StopVideoResponse - virtual ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -326,47 +264,7 @@ class CameraServerService final { ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; - template - class WithAsyncMethod_SubscribeStartVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodAsync(4); - } - ~WithAsyncMethod_SubscribeStartVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeStartVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(4, context, request, writer, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_SubscribeStopVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodAsync(5); - } - ~WithAsyncMethod_SubscribeStopVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeStopVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); - } - }; - typedef WithAsyncMethod_SetInformation > > > > > AsyncService; + typedef WithAsyncMethod_SetInformation > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -470,51 +368,7 @@ class CameraServerService final { virtual ::grpc::ServerUnaryReactor* RespondTakePhoto( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) { return nullptr; } }; - template - class WithCallbackMethod_SubscribeStartVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodCallback(4, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request) { return this->SubscribeStartVideo(context, request); })); - } - ~WithCallbackMethod_SubscribeStartVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideo( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/) { return nullptr; } - }; - template - class WithCallbackMethod_SubscribeStopVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodCallback(5, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request) { return this->SubscribeStopVideo(context, request); })); - } - ~WithCallbackMethod_SubscribeStopVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideo( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/) { return nullptr; } - }; - typedef WithCallbackMethod_SetInformation > > > > > CallbackService; + typedef WithCallbackMethod_SetInformation > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -585,40 +439,6 @@ class CameraServerService final { } }; template - class WithGenericMethod_SubscribeStartVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodGeneric(4); - } - ~WithGenericMethod_SubscribeStartVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template - class WithGenericMethod_SubscribeStopVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodGeneric(5); - } - ~WithGenericMethod_SubscribeStopVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template class WithRawMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -699,46 +519,6 @@ class CameraServerService final { } }; template - class WithRawMethod_SubscribeStartVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodRaw(4); - } - ~WithRawMethod_SubscribeStartVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeStartVideo(::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(4, context, request, writer, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_SubscribeStopVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodRaw(5); - } - ~WithRawMethod_SubscribeStopVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeStopVideo(::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(5, context, request, writer, new_call_cq, notification_cq, tag); - } - }; - template class WithRawCallbackMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -827,50 +607,6 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SubscribeStartVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodRawCallback(4, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStartVideo(context, request); })); - } - ~WithRawCallbackMethod_SubscribeStartVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeStartVideo( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } - }; - template - class WithRawCallbackMethod_SubscribeStopVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodRawCallback(5, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStopVideo(context, request); })); - } - ~WithRawCallbackMethod_SubscribeStopVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeStopVideo( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } - }; - template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -979,62 +715,8 @@ class CameraServerService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeTakePhoto(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest,::mavsdk::rpc::camera_server::TakePhotoResponse>* server_split_streamer) = 0; }; - template - class WithSplitStreamingMethod_SubscribeStartVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithSplitStreamingMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodStreamed(4, - new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>* streamer) { - return this->StreamedSubscribeStartVideo(context, - streamer); - })); - } - ~WithSplitStreamingMethod_SubscribeStartVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeStartVideo(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest,::mavsdk::rpc::camera_server::StartVideoResponse>* server_split_streamer) = 0; - }; - template - class WithSplitStreamingMethod_SubscribeStopVideo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithSplitStreamingMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodStreamed(5, - new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>* streamer) { - return this->StreamedSubscribeStopVideo(context, - streamer); - })); - } - ~WithSplitStreamingMethod_SubscribeStopVideo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeStopVideo(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest,::mavsdk::rpc::camera_server::StopVideoResponse>* server_split_streamer) = 0; - }; - typedef WithSplitStreamingMethod_SubscribeTakePhoto > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > StreamedService; + typedef WithSplitStreamingMethod_SubscribeTakePhoto SplitStreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index c544e417c9..a019c2673b 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -115,64 +115,6 @@ struct TakePhotoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; template -PROTOBUF_CONSTEXPR SubscribeStartVideoRequest::SubscribeStartVideoRequest( - ::_pbi::ConstantInitialized) {} -struct SubscribeStartVideoRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeStartVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeStartVideoRequestDefaultTypeInternal() {} - union { - SubscribeStartVideoRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeStartVideoRequestDefaultTypeInternal _SubscribeStartVideoRequest_default_instance_; -template -PROTOBUF_CONSTEXPR StartVideoResponse::StartVideoResponse( - ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_.stream_id_)*/ 0 - - , /*decltype(_impl_._cached_size_)*/{}} {} -struct StartVideoResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR StartVideoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~StartVideoResponseDefaultTypeInternal() {} - union { - StartVideoResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; -template -PROTOBUF_CONSTEXPR SubscribeStopVideoRequest::SubscribeStopVideoRequest( - ::_pbi::ConstantInitialized) {} -struct SubscribeStopVideoRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeStopVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeStopVideoRequestDefaultTypeInternal() {} - union { - SubscribeStopVideoRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeStopVideoRequestDefaultTypeInternal _SubscribeStopVideoRequest_default_instance_; -template -PROTOBUF_CONSTEXPR StopVideoResponse::StopVideoResponse( - ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_.stream_id_)*/ 0 - - , /*decltype(_impl_._cached_size_)*/{}} {} -struct StopVideoResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR StopVideoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~StopVideoResponseDefaultTypeInternal() {} - union { - StopVideoResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; -template PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} @@ -344,7 +286,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; @@ -406,40 +348,6 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, _impl_.index_), - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, _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::camera_server::StartVideoResponse, _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::camera_server::StartVideoResponse, _impl_.stream_id_), - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, _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::camera_server::StopVideoResponse, _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::camera_server::StopVideoResponse, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -545,17 +453,13 @@ static const ::_pbi::MigrationSchema { 29, 38, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, { 39, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, { 47, -1, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, - { 56, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, - { 64, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, - { 73, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, - { 81, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, - { 90, 100, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 102, 111, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 112, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 131, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 143, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 155, 169, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 175, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 56, 66, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 68, 77, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 78, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 97, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 109, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 121, 135, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 141, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -565,10 +469,6 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_SetInProgressResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_TakePhotoResponse_default_instance_._instance, - &::mavsdk::rpc::camera_server::_SubscribeStartVideoRequest_default_instance_._instance, - &::mavsdk::rpc::camera_server::_StartVideoResponse_default_instance_._instance, - &::mavsdk::rpc::camera_server::_SubscribeStopVideoRequest_default_instance_._instance, - &::mavsdk::rpc::camera_server::_StopVideoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, @@ -590,65 +490,55 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "sult\030\001 \001(\0132,.mavsdk.rpc.camera_server.Ca" "meraServerResult\"\033\n\031SubscribeTakePhotoRe" "quest\"\"\n\021TakePhotoResponse\022\r\n\005index\030\001 \001(" - "\005\"\034\n\032SubscribeStartVideoRequest\"\'\n\022Start" - "VideoResponse\022\021\n\tstream_id\030\001 \001(\005\"\033\n\031Subs" - "cribeStopVideoRequest\"&\n\021StopVideoRespon" - "se\022\021\n\tstream_id\030\001 \001(\005\"\240\001\n\027RespondTakePho" - "toRequest\022H\n\023take_photo_feedback\030\001 \001(\0162+" - ".mavsdk.rpc.camera_server.TakePhotoFeedb" - "ack\022;\n\014capture_info\030\002 \001(\0132%.mavsdk.rpc.c" - "amera_server.CaptureInfo\"f\n\030RespondTakeP" - "hotoResponse\022J\n\024camera_server_result\030\001 \001" - "(\0132,.mavsdk.rpc.camera_server.CameraServ" - "erResult\"\276\002\n\013Information\022\023\n\013vendor_name\030" - "\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\030\n\020firmware_ve" - "rsion\030\003 \001(\t\022\027\n\017focal_length_mm\030\004 \001(\002\022!\n\031" - "horizontal_sensor_size_mm\030\005 \001(\002\022\037\n\027verti" - "cal_sensor_size_mm\030\006 \001(\002\022 \n\030horizontal_r" - "esolution_px\030\007 \001(\r\022\036\n\026vertical_resolutio" - "n_px\030\010 \001(\r\022\017\n\007lens_id\030\t \001(\r\022\037\n\027definitio" - "n_file_version\030\n \001(\r\022\033\n\023definition_file_" - "uri\030\013 \001(\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 " - "\001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_a" - "ltitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004" - " \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002" - "\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224" - "\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_ser" - "ver.Position\022A\n\023attitude_quaternion\030\002 \001(" - "\0132$.mavsdk.rpc.camera_server.Quaternion\022" - "\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010" - "\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022Ca" - "meraServerResult\022C\n\006result\030\001 \001(\01623.mavsd" - "k.rpc.camera_server.CameraServerResult.R" - "esult\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016" - "RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022" - "RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n" - "\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RE" - "SULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020" - "\007\022\024\n\020RESULT_NO_SYSTEM\020\010*\216\001\n\021TakePhotoFee" - "dback\022\037\n\033TAKE_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032" - "\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO" - "_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_" - "FAILED\020\0032\215\006\n\023CameraServerService\022y\n\016SetI" - "nformation\022/.mavsdk.rpc.camera_server.Se" - "tInformationRequest\0320.mavsdk.rpc.camera_" - "server.SetInformationResponse\"\004\200\265\030\001\022v\n\rS" - "etInProgress\022..mavsdk.rpc.camera_server." - "SetInProgressRequest\032/.mavsdk.rpc.camera" - "_server.SetInProgressResponse\"\004\200\265\030\001\022~\n\022S" - "ubscribeTakePhoto\0223.mavsdk.rpc.camera_se" - "rver.SubscribeTakePhotoRequest\032+.mavsdk." - "rpc.camera_server.TakePhotoResponse\"\004\200\265\030" - "\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk.rpc.cam" - "era_server.RespondTakePhotoRequest\0322.mav" - "sdk.rpc.camera_server.RespondTakePhotoRe" - "sponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVideo\0224.m" - "avsdk.rpc.camera_server.SubscribeStartVi" - "deoRequest\032,.mavsdk.rpc.camera_server.St" - "artVideoResponse\"\004\200\265\030\0000\001\022~\n\022SubscribeSto" - "pVideo\0223.mavsdk.rpc.camera_server.Subscr" - "ibeStopVideoRequest\032+.mavsdk.rpc.camera_" - "server.StopVideoResponse\"\004\200\265\030\0000\001B,\n\027io.m" + "\005\"\240\001\n\027RespondTakePhotoRequest\022H\n\023take_ph" + "oto_feedback\030\001 \001(\0162+.mavsdk.rpc.camera_s" + "erver.TakePhotoFeedback\022;\n\014capture_info\030" + "\002 \001(\0132%.mavsdk.rpc.camera_server.Capture" + "Info\"f\n\030RespondTakePhotoResponse\022J\n\024came" + "ra_server_result\030\001 \001(\0132,.mavsdk.rpc.came" + "ra_server.CameraServerResult\"\276\002\n\013Informa" + "tion\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030" + "\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal" + "_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_si" + "ze_mm\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006" + " \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r\022\036" + "\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens_i" + "d\030\t \001(\r\022\037\n\027definition_file_version\030\n \001(\r" + "\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n\010Positio" + "n\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg" + "\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023r" + "elative_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t" + "\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001" + "(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".m" + "avsdk.rpc.camera_server.Position\022A\n\023atti" + "tude_quaternion\030\002 \001(\0132$.mavsdk.rpc.camer" + "a_server.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004" + "\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010f" + "ile_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006" + "result\030\001 \001(\01623.mavsdk.rpc.camera_server." + "CameraServerResult.Result\022\022\n\nresult_str\030" + "\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016" + "RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002" + "\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014" + "RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RE" + "SULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTE" + "M\020\010*\216\001\n\021TakePhotoFeedback\022\037\n\033TAKE_PHOTO_" + "FEEDBACK_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO_FEEDBAC" + "K_OK\020\001\022\034\n\030TAKE_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032" + "TAKE_PHOTO_FEEDBACK_FAILED\020\0032\211\004\n\023CameraS" + "erverService\022y\n\016SetInformation\022/.mavsdk." + "rpc.camera_server.SetInformationRequest\032" + "0.mavsdk.rpc.camera_server.SetInformatio" + "nResponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsd" + "k.rpc.camera_server.SetInProgressRequest" + "\032/.mavsdk.rpc.camera_server.SetInProgres" + "sResponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223." + "mavsdk.rpc.camera_server.SubscribeTakePh" + "otoRequest\032+.mavsdk.rpc.camera_server.Ta" + "kePhotoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePh" + "oto\0221.mavsdk.rpc.camera_server.RespondTa" + "kePhotoRequest\0322.mavsdk.rpc.camera_serve" + "r.RespondTakePhotoResponse\"\004\200\265\030\001B,\n\027io.m" "avsdk.camera_serverB\021CameraServerProtob\006" "proto3" }; @@ -660,13 +550,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 2886, + 2486, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 17, + 13, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -1750,430 +1640,6 @@ ::PROTOBUF_NAMESPACE_ID::Metadata TakePhotoResponse::GetMetadata() const { } // =================================================================== -class SubscribeStartVideoRequest::_Internal { - public: -}; - -SubscribeStartVideoRequest::SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) -} -SubscribeStartVideoRequest::SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeStartVideoRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStartVideoRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); -} -// =================================================================== - -class StartVideoResponse::_Internal { - public: -}; - -StartVideoResponse::StartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StartVideoResponse) -} -StartVideoResponse::StartVideoResponse(const StartVideoResponse& 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.camera_server.StartVideoResponse) -} - -inline void StartVideoResponse::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_.stream_id_) { 0 } - - , /*decltype(_impl_._cached_size_)*/{} - }; -} - -StartVideoResponse::~StartVideoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StartVideoResponse) - if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { - (void)arena; - return; - } - SharedDtor(); -} - -inline void StartVideoResponse::SharedDtor() { - ABSL_DCHECK(GetArenaForAllocation() == nullptr); -} - -void StartVideoResponse::SetCachedSize(int size) const { - _impl_._cached_size_.Set(size); -} - -void StartVideoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StartVideoResponse) - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - _impl_.stream_id_ = 0; - _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); -} - -const char* StartVideoResponse::_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) { - // int32 stream_id = 1; - case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.stream_id_ = ::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* StartVideoResponse::_InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StartVideoResponse) - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_stream_id(), 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.camera_server.StartVideoResponse) - return target; -} - -::size_t StartVideoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StartVideoResponse) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_stream_id()); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoResponse::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - StartVideoResponse::MergeImpl -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoResponse::GetClassData() const { return &_class_data_; } - - -void StartVideoResponse::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.camera_server.StartVideoResponse) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - if (from._internal_stream_id() != 0) { - _this->_internal_set_stream_id(from._internal_stream_id()); - } - _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); -} - -void StartVideoResponse::CopyFrom(const StartVideoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StartVideoResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool StartVideoResponse::IsInitialized() const { - return true; -} - -void StartVideoResponse::InternalSwap(StartVideoResponse* other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - - swap(_impl_.stream_id_, other->_impl_.stream_id_); -} - -::PROTOBUF_NAMESPACE_ID::Metadata StartVideoResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); -} -// =================================================================== - -class SubscribeStopVideoRequest::_Internal { - public: -}; - -SubscribeStopVideoRequest::SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) -} -SubscribeStopVideoRequest::SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeStopVideoRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStopVideoRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); -} -// =================================================================== - -class StopVideoResponse::_Internal { - public: -}; - -StopVideoResponse::StopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StopVideoResponse) -} -StopVideoResponse::StopVideoResponse(const StopVideoResponse& 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.camera_server.StopVideoResponse) -} - -inline void StopVideoResponse::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_.stream_id_) { 0 } - - , /*decltype(_impl_._cached_size_)*/{} - }; -} - -StopVideoResponse::~StopVideoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StopVideoResponse) - if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { - (void)arena; - return; - } - SharedDtor(); -} - -inline void StopVideoResponse::SharedDtor() { - ABSL_DCHECK(GetArenaForAllocation() == nullptr); -} - -void StopVideoResponse::SetCachedSize(int size) const { - _impl_._cached_size_.Set(size); -} - -void StopVideoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StopVideoResponse) - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - _impl_.stream_id_ = 0; - _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); -} - -const char* StopVideoResponse::_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) { - // int32 stream_id = 1; - case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.stream_id_ = ::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* StopVideoResponse::_InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StopVideoResponse) - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_stream_id(), 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.camera_server.StopVideoResponse) - return target; -} - -::size_t StopVideoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StopVideoResponse) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_stream_id()); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoResponse::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - StopVideoResponse::MergeImpl -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoResponse::GetClassData() const { return &_class_data_; } - - -void StopVideoResponse::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.camera_server.StopVideoResponse) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - if (from._internal_stream_id() != 0) { - _this->_internal_set_stream_id(from._internal_stream_id()); - } - _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); -} - -void StopVideoResponse::CopyFrom(const StopVideoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StopVideoResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool StopVideoResponse::IsInitialized() const { - return true; -} - -void StopVideoResponse::InternalSwap(StopVideoResponse* other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - - swap(_impl_.stream_id_, other->_impl_.stream_id_); -} - -::PROTOBUF_NAMESPACE_ID::Metadata StopVideoResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); -} -// =================================================================== - class RespondTakePhotoRequest::_Internal { public: using HasBits = decltype(std::declval()._impl_._has_bits_); @@ -2412,7 +1878,7 @@ void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); } // =================================================================== @@ -2617,7 +2083,7 @@ void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); } // =================================================================== @@ -3202,7 +2668,7 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); } // =================================================================== @@ -3507,7 +2973,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); } // =================================================================== @@ -3812,7 +3278,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); } // =================================================================== @@ -4215,7 +3681,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); } // =================================================================== @@ -4444,7 +3910,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -4475,22 +3941,6 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::TakePhotoResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::TakePhotoResponse >(arena); } -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* -Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest >(arena); -} -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StartVideoResponse* -Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StartVideoResponse >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StartVideoResponse >(arena); -} -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* -Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest >(arena); -} -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StopVideoResponse* -Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StopVideoResponse >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StopVideoResponse >(arena); -} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index cc3322ae0c..4e6ce34cd4 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -89,18 +89,6 @@ extern SetInformationRequestDefaultTypeInternal _SetInformationRequest_default_i class SetInformationResponse; struct SetInformationResponseDefaultTypeInternal; extern SetInformationResponseDefaultTypeInternal _SetInformationResponse_default_instance_; -class StartVideoResponse; -struct StartVideoResponseDefaultTypeInternal; -extern StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; -class StopVideoResponse; -struct StopVideoResponseDefaultTypeInternal; -extern StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; -class SubscribeStartVideoRequest; -struct SubscribeStartVideoRequestDefaultTypeInternal; -extern SubscribeStartVideoRequestDefaultTypeInternal _SubscribeStartVideoRequest_default_instance_; -class SubscribeStopVideoRequest; -struct SubscribeStopVideoRequestDefaultTypeInternal; -extern SubscribeStopVideoRequestDefaultTypeInternal _SubscribeStopVideoRequest_default_instance_; class SubscribeTakePhotoRequest; struct SubscribeTakePhotoRequestDefaultTypeInternal; extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_default_instance_; @@ -134,14 +122,6 @@ ::mavsdk::rpc::camera_server::SetInformationRequest* Arena::CreateMaybeMessage<: template <> ::mavsdk::rpc::camera_server::SetInformationResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInformationResponse>(Arena*); template <> -::mavsdk::rpc::camera_server::StartVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoResponse>(Arena*); -template <> -::mavsdk::rpc::camera_server::StopVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StopVideoResponse>(Arena*); -template <> -::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoRequest>(Arena*); -template <> -::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStopVideoRequest>(Arena*); -template <> ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::TakePhotoResponse>(Arena*); @@ -1143,564 +1123,6 @@ class TakePhotoResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStartVideoRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) */ { - public: - inline SubscribeStartVideoRequest() : SubscribeStartVideoRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from); - SubscribeStartVideoRequest(SubscribeStartVideoRequest&& from) noexcept - : SubscribeStartVideoRequest() { - *this = ::std::move(from); - } - - inline SubscribeStartVideoRequest& operator=(const SubscribeStartVideoRequest& from) { - CopyFrom(from); - return *this; - } - inline SubscribeStartVideoRequest& operator=(SubscribeStartVideoRequest&& 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 SubscribeStartVideoRequest& default_instance() { - return *internal_default_instance(); - } - static inline const SubscribeStartVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStartVideoRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 6; - - friend void swap(SubscribeStartVideoRequest& a, SubscribeStartVideoRequest& b) { - a.Swap(&b); - } - inline void Swap(SubscribeStartVideoRequest* 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(SubscribeStartVideoRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - SubscribeStartVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStartVideoRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStartVideoRequest& 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.camera_server.SubscribeStartVideoRequest"; - } - protected: - explicit SubscribeStartVideoRequest(::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.camera_server.SubscribeStartVideoRequest) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - }; - friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class StartVideoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoResponse) */ { - public: - inline StartVideoResponse() : StartVideoResponse(nullptr) {} - ~StartVideoResponse() override; - template - explicit PROTOBUF_CONSTEXPR StartVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - StartVideoResponse(const StartVideoResponse& from); - StartVideoResponse(StartVideoResponse&& from) noexcept - : StartVideoResponse() { - *this = ::std::move(from); - } - - inline StartVideoResponse& operator=(const StartVideoResponse& from) { - CopyFrom(from); - return *this; - } - inline StartVideoResponse& operator=(StartVideoResponse&& 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 StartVideoResponse& default_instance() { - return *internal_default_instance(); - } - static inline const StartVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_StartVideoResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 7; - - friend void swap(StartVideoResponse& a, StartVideoResponse& b) { - a.Swap(&b); - } - inline void Swap(StartVideoResponse* 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(StartVideoResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - StartVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StartVideoResponse& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StartVideoResponse& from) { - StartVideoResponse::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(StartVideoResponse* other); - - private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StartVideoResponse"; - } - protected: - explicit StartVideoResponse(::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 { - kStreamIdFieldNumber = 1, - }; - // int32 stream_id = 1; - void clear_stream_id() ; - ::int32_t stream_id() const; - void set_stream_id(::int32_t value); - - private: - ::int32_t _internal_stream_id() const; - void _internal_set_stream_id(::int32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoResponse) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::int32_t stream_id_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class SubscribeStopVideoRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) */ { - public: - inline SubscribeStopVideoRequest() : SubscribeStopVideoRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from); - SubscribeStopVideoRequest(SubscribeStopVideoRequest&& from) noexcept - : SubscribeStopVideoRequest() { - *this = ::std::move(from); - } - - inline SubscribeStopVideoRequest& operator=(const SubscribeStopVideoRequest& from) { - CopyFrom(from); - return *this; - } - inline SubscribeStopVideoRequest& operator=(SubscribeStopVideoRequest&& 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 SubscribeStopVideoRequest& default_instance() { - return *internal_default_instance(); - } - static inline const SubscribeStopVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStopVideoRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 8; - - friend void swap(SubscribeStopVideoRequest& a, SubscribeStopVideoRequest& b) { - a.Swap(&b); - } - inline void Swap(SubscribeStopVideoRequest* 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(SubscribeStopVideoRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - SubscribeStopVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStopVideoRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStopVideoRequest& 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.camera_server.SubscribeStopVideoRequest"; - } - protected: - explicit SubscribeStopVideoRequest(::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.camera_server.SubscribeStopVideoRequest) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - }; - friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class StopVideoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoResponse) */ { - public: - inline StopVideoResponse() : StopVideoResponse(nullptr) {} - ~StopVideoResponse() override; - template - explicit PROTOBUF_CONSTEXPR StopVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - StopVideoResponse(const StopVideoResponse& from); - StopVideoResponse(StopVideoResponse&& from) noexcept - : StopVideoResponse() { - *this = ::std::move(from); - } - - inline StopVideoResponse& operator=(const StopVideoResponse& from) { - CopyFrom(from); - return *this; - } - inline StopVideoResponse& operator=(StopVideoResponse&& 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 StopVideoResponse& default_instance() { - return *internal_default_instance(); - } - static inline const StopVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_StopVideoResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 9; - - friend void swap(StopVideoResponse& a, StopVideoResponse& b) { - a.Swap(&b); - } - inline void Swap(StopVideoResponse* 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(StopVideoResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - StopVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StopVideoResponse& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StopVideoResponse& from) { - StopVideoResponse::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(StopVideoResponse* other); - - private: - friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StopVideoResponse"; - } - protected: - explicit StopVideoResponse(::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 { - kStreamIdFieldNumber = 1, - }; - // int32 stream_id = 1; - void clear_stream_id() ; - ::int32_t stream_id() const; - void set_stream_id(::int32_t value); - - private: - ::int32_t _internal_stream_id() const; - void _internal_set_stream_id(::int32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoResponse) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::int32_t stream_id_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; -};// ------------------------------------------------------------------- - class RespondTakePhotoRequest final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { public: @@ -1757,7 +1179,7 @@ class RespondTakePhotoRequest final : &_RespondTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 6; friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { a.Swap(&b); @@ -1929,7 +1351,7 @@ class RespondTakePhotoResponse final : &_RespondTakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 7; friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { a.Swap(&b); @@ -2089,7 +1511,7 @@ class Information final : &_Information_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 8; friend void swap(Information& a, Information& b) { a.Swap(&b); @@ -2404,7 +1826,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 9; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -2595,7 +2017,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 10; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -2786,7 +2208,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 11; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -3020,7 +2442,7 @@ class CameraServerResult final : &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 12; friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); @@ -3507,62 +2929,6 @@ inline void TakePhotoResponse::_internal_set_index(::int32_t value) { // ------------------------------------------------------------------- -// SubscribeStartVideoRequest - -// ------------------------------------------------------------------- - -// StartVideoResponse - -// int32 stream_id = 1; -inline void StartVideoResponse::clear_stream_id() { - _impl_.stream_id_ = 0; -} -inline ::int32_t StartVideoResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) - return _internal_stream_id(); -} -inline void StartVideoResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) -} -inline ::int32_t StartVideoResponse::_internal_stream_id() const { - return _impl_.stream_id_; -} -inline void StartVideoResponse::_internal_set_stream_id(::int32_t value) { - ; - _impl_.stream_id_ = value; -} - -// ------------------------------------------------------------------- - -// SubscribeStopVideoRequest - -// ------------------------------------------------------------------- - -// StopVideoResponse - -// int32 stream_id = 1; -inline void StopVideoResponse::clear_stream_id() { - _impl_.stream_id_ = 0; -} -inline ::int32_t StopVideoResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) - return _internal_stream_id(); -} -inline void StopVideoResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) -} -inline ::int32_t StopVideoResponse::_internal_stream_id() const { - return _impl_.stream_id_; -} -inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { - ; - _impl_.stream_id_ = value; -} - -// ------------------------------------------------------------------- - // RespondTakePhotoRequest // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 84e1cf9144..39ddeb1f55 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -437,88 +437,6 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } - grpc::Status SubscribeStartVideo( - grpc::ServerContext* /* context */, - const mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /* request */, - grpc::ServerWriter* writer) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - return grpc::Status::OK; - } - - auto stream_closed_promise = std::make_shared>(); - auto stream_closed_future = stream_closed_promise->get_future(); - register_stream_stop_promise(stream_closed_promise); - - auto is_finished = std::make_shared(false); - auto subscribe_mutex = std::make_shared(); - - const mavsdk::CameraServer::StartVideoHandle handle = - _lazy_plugin.maybe_plugin()->subscribe_start_video( - [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const int32_t start_video) { - rpc::camera_server::StartVideoResponse rpc_response; - - rpc_response.set_stream_id(start_video); - - std::unique_lock lock(*subscribe_mutex); - if (!*is_finished && !writer->Write(rpc_response)) { - _lazy_plugin.maybe_plugin()->unsubscribe_start_video(handle); - - *is_finished = true; - unregister_stream_stop_promise(stream_closed_promise); - stream_closed_promise->set_value(); - } - }); - - stream_closed_future.wait(); - std::unique_lock lock(*subscribe_mutex); - *is_finished = true; - - return grpc::Status::OK; - } - - grpc::Status SubscribeStopVideo( - grpc::ServerContext* /* context */, - const mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /* request */, - grpc::ServerWriter* writer) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - return grpc::Status::OK; - } - - auto stream_closed_promise = std::make_shared>(); - auto stream_closed_future = stream_closed_promise->get_future(); - register_stream_stop_promise(stream_closed_promise); - - auto is_finished = std::make_shared(false); - auto subscribe_mutex = std::make_shared(); - - const mavsdk::CameraServer::StopVideoHandle handle = - _lazy_plugin.maybe_plugin()->subscribe_stop_video( - [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const int32_t stop_video) { - rpc::camera_server::StopVideoResponse rpc_response; - - rpc_response.set_stream_id(stop_video); - - std::unique_lock lock(*subscribe_mutex); - if (!*is_finished && !writer->Write(rpc_response)) { - _lazy_plugin.maybe_plugin()->unsubscribe_stop_video(handle); - - *is_finished = true; - unregister_stream_stop_promise(stream_closed_promise); - stream_closed_promise->set_value(); - } - }); - - stream_closed_future.wait(); - std::unique_lock lock(*subscribe_mutex); - *is_finished = true; - - return grpc::Status::OK; - } - void stop() { _stopped.store(true); diff --git a/src/system_tests/ftp_list_dir.cpp b/src/system_tests/ftp_list_dir.cpp index 4d1a4dcafb..ef7dbc7623 100644 --- a/src/system_tests/ftp_list_dir.cpp +++ b/src/system_tests/ftp_list_dir.cpp @@ -50,7 +50,6 @@ TEST(SystemTest, FtpListDir) 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)));