diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..3b4d564 --- /dev/null +++ b/.clang-format @@ -0,0 +1,5 @@ +--- +Language: Cpp +BasedOnStyle: Google +SortIncludes: false + diff --git a/.github/workflows/linux_cpp_build.yml b/.github/workflows/linux_cpp_build.yml index 62d305a..d27c17f 100644 --- a/.github/workflows/linux_cpp_build.yml +++ b/.github/workflows/linux_cpp_build.yml @@ -4,26 +4,8 @@ on: workflow_dispatch: pull_request: jobs: - linux_cpp_build: - runs-on: ubuntu-latest - steps: - - name: Checkout - uses: actions/checkout@v3 - - - name: install components - run: sudo apt-get install -y build-essential doxygen graphviz python3-pip python3-dev - - - name: install dependencies - run: pip3 install -r requirements.txt - - - name: configure - run: cmake -S. -Bbuild -DBUILD_DEB=ON - - - name: build - run: cmake --build build - linux_cpp_test: - needs: linux_cpp_build + # needs: linux_cpp_build runs-on: ubuntu-latest container: registry.cn-shanghai.aliyuncs.com/lebai/l-master:3.1.6 steps: @@ -52,3 +34,31 @@ jobs: - name: test run: cmake --build build --target test + + linux_cpp_build: + runs-on: ubuntu-latest + steps: + - name: Checkout + uses: actions/checkout@v3 + + - name: install components + run: sudo apt-get install -y build-essential doxygen graphviz python3-pip python3-dev + + - name: install dependencies + run: | + pip3 install -r requirements.txt + pip3 install clang-format + + - name: configure + run: cmake -S. -Bbuild -DBUILD_DEB=ON -DCLANG_FORMAT_CHECK=ON + + - name: build + run: | + cmake --build build + cd build && cpack && cd .. + # - name: Upload deb + # uses: actions/upload-artifact@v4 + # id: artifact + # with: + # name: lebai-deb-package + # path: build/*.deb \ No newline at end of file diff --git a/.github/workflows/linux_cpp_release.yml b/.github/workflows/linux_cpp_release.yml index 1f68615..8c3bbc9 100644 --- a/.github/workflows/linux_cpp_release.yml +++ b/.github/workflows/linux_cpp_release.yml @@ -66,7 +66,12 @@ jobs: run: cpack --config ./build/CPackConfig.cmake - name: upload .deb - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: - name: DebForCPP - path: ./*.deb \ No newline at end of file + name: lebai-deb-package + path: *.deb + - name: release + uses: ncipollo/release-action@v1 + with: + artifacts: *.deb + allowUpdates: true \ No newline at end of file diff --git a/.gitignore b/.gitignore index a61307b..51224d0 100644 --- a/.gitignore +++ b/.gitignore @@ -3,4 +3,5 @@ out .vscode .vs sdk/include/lebai/config.hh -CMakeSettings.json \ No newline at end of file +CMakeSettings.json +.cache diff --git a/CMakeLists.txt b/CMakeLists.txt index 6453565..651a4c5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,37 +1,41 @@ -cmake_minimum_required(VERSION 3.18) -if (POLICY CMP0122) +cmake_minimum_required(VERSION 3.15) +if(POLICY CMP0122) cmake_policy(SET CMP0122 NEW) endif() -if (POLICY CMP0135) +if(POLICY CMP0135) cmake_policy(SET CMP0135 NEW) endif() -project(lebai VERSION 1.1.24 LANGUAGES CXX) +project( + lebai + VERSION 1.1.25 + LANGUAGES CXX) list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") option(CMAKE_EXPORT_COMPILE_COMMANDS "Export compile command" TRUE) set(PROJECT_NAMESPACE lebai) -message(STATUS "${PROJECT_NAME} version: ${PROJECT_VERSION}") -# message(STATUS "major: ${PROJECT_VERSION_MAJOR}") -# message(STATUS "minor: ${PROJECT_VERSION_MINOR}") -# message(STATUS "patch: ${PROJECT_VERSION_PATCH}") - get_property(isMultiConfig GLOBAL PROPERTY GENERATOR_IS_MULTI_CONFIG) if(isMultiConfig) if(NOT CMAKE_CONFIGURATION_TYPES) - set(CMAKE_CONFIGURATION_TYPES "Release;Debug" CACHE STRING - "Choose the type of builds, options are: Debug Release RelWithDebInfo MinSizeRel. (default: Release;Debug)" - FORCE) + set(CMAKE_CONFIGURATION_TYPES + "Release;Debug" + CACHE + STRING + "Choose the type of builds, options are: Debug Release RelWithDebInfo MinSizeRel. (default: Release;Debug)" + FORCE) endif() message(STATUS "Configuration types: ${CMAKE_CONFIGURATION_TYPES}") else() if(NOT CMAKE_BUILD_TYPE) - set(CMAKE_BUILD_TYPE "Release" CACHE STRING - "Choose the type of build, options are: Debug Release RelWithDebInfo MinSizeRel. (default: Release)" - FORCE) + set(CMAKE_BUILD_TYPE + "Release" + CACHE + STRING + "Choose the type of build, options are: Debug Release RelWithDebInfo MinSizeRel. (default: Release)" + FORCE) endif() message(STATUS "Build type: ${CMAKE_BUILD_TYPE}") endif() @@ -41,37 +45,48 @@ include(GNUInstallDirs) if(UNIX) option(BUILD_SHARED_LIBS "Build shared libraries (.so or .dyld)." ON) set(CMAKE_BUILD_WITH_INSTALL_RPATH TRUE) - set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_LIBDIR}) - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_LIBDIR}) - set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY + ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_LIBDIR}) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY + ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_LIBDIR}) + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY + ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) # for multi-config build system (e.g. Xcode, Ninja Multi-Config) foreach(OutputConfig IN LISTS CMAKE_CONFIGURATION_TYPES) string(TOUPPER ${OutputConfig} OUTPUTCONFIG) - set(CMAKE_LIBRARY_OUTPUT_DIRECTORY_${OUTPUTCONFIG} ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_LIBDIR}) - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY_${OUTPUTCONFIG} ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_LIBDIR}) - set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_${OUTPUTCONFIG} ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY_${OUTPUTCONFIG} + ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_LIBDIR}) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY_${OUTPUTCONFIG} + ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_LIBDIR}) + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_${OUTPUTCONFIG} + ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) endforeach() else() # Currently Only support static build for windows option(BUILD_SHARED_LIBS "Build shared libraries (.dll)." OFF) add_compile_definitions(_USE_MATH_DEFINES) add_compile_definitions(_WEBSOCKETPP_CPP11_RANDOM_DEVICE_) - # add_compile_definitions(NOMINMAX) - # add_compile_definitions(_DEBUG) + # add_compile_definitions(NOMINMAX) add_compile_definitions(_DEBUG) if(WIN32) add_definitions(-D_WIN32_WINNT=0x0601) endif() add_compile_options("$<$:/utf-8>") add_compile_options("$<$:/utf-8>") - set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) - set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY + ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY + ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY + ${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}) # for multi-config builds (e.g. msvc) foreach(OutputConfig IN LISTS CMAKE_CONFIGURATION_TYPES) string(TOUPPER ${OutputConfig} OUTPUTCONFIG) - set(CMAKE_LIBRARY_OUTPUT_DIRECTORY_${OUTPUTCONFIG} ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY_${OUTPUTCONFIG} ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) - set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_${OUTPUTCONFIG} ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY_${OUTPUTCONFIG} + ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY_${OUTPUTCONFIG} + ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_${OUTPUTCONFIG} + ${CMAKE_BINARY_DIR}/${OutputConfig}/${CMAKE_INSTALL_BINDIR}) endforeach() endif() @@ -101,44 +116,46 @@ message(STATUS "Build Java: ${BUILD_JAVA}") if(BUILD_PYTHON AND BUILD_PYTHON2) message(FATAL_ERROR "Can only build one of python2 and python3.") endif() -#if(UNIX) - if(BUILD_PYTHON) - option(FETCH_PYTHON_DEPS "Install python required modules if not available" ON) - message(STATUS "Python fetch dependencies: ${FETCH_PYTHON_DEPS}") - if(DEFINED PYTHONPATH) - message(STATUS "Python path: ${PYTHONPATH}") - set(Python3_ROOT_DIR ${PYTHONPATH}) - endif() - include(python) - endif() - - if(BUILD_PYTHON2) - if(DEFINED PYTHONPATH) - message(STATUS "Python path: ${PYTHON2PATH}") - set(Python2_ROOT_DIR ${PYTHONPATH}) - endif() - include(python2) - endif() -#endif() -# Disable CTest targets +# if(UNIX) +if(BUILD_PYTHON) + option(FETCH_PYTHON_DEPS "Install python required modules if not available" + ON) + message(STATUS "Python fetch dependencies: ${FETCH_PYTHON_DEPS}") + if(DEFINED PYTHONPATH) + message(STATUS "Python path: ${PYTHONPATH}") + set(Python3_ROOT_DIR ${PYTHONPATH}) + endif() + include(python) +endif() + +if(BUILD_PYTHON2) + if(DEFINED PYTHONPATH) + message(STATUS "Python path: ${PYTHON2PATH}") + set(Python2_ROOT_DIR ${PYTHONPATH}) + endif() + include(python2) +endif() +# endif() Disable CTest targets set_property(GLOBAL PROPERTY CTEST_TARGETS_ADDED 1) include(CTest) include(cpp) -if(WIN32 AND (BUILD_DOTNET OR BUILD_JAVA OR BUILD_PYTHON)) +if(WIN32 + AND (BUILD_DOTNET + OR BUILD_JAVA + OR BUILD_PYTHON)) message(STATUS "Getting SWIG: ...") - #add_definitions(-DSWIG_PYTHON_INTERPRETER_NO_DEBUG) + # add_definitions(-DSWIG_PYTHON_INTERPRETER_NO_DEBUG) include(swig) message(STATUS "Getting SWIG: ...DONE") endif() - if(BUILD_PYTHON) - option(FETCH_PYTHON_DEPS "Install python required modules if not available" ON) + option(FETCH_PYTHON_DEPS "Install python required modules if not available" + ON) message(STATUS "Python fetch dependencies: ${FETCH_PYTHON_DEPS}") endif() - if(BUILD_DOTNET) # .Net Core 3.1 LTS is not available for osx arm64 if(APPLE AND CMAKE_SYSTEM_PROCESSOR MATCHES "^(aarch64|arm64)") @@ -159,36 +176,59 @@ if(BUILD_JAVA) endif() include(java) - # add_subdirectory(tests) option(BUILD_EXAMPLES "Build examples" ON) message(STATUS "Build examples: ${BUILD_EXAMPLES}") add_subdirectory(examples) +set(SDK_DIR "${CMAKE_SOURCE_DIR}/sdk") +# Get all .cc, .c, .cpp, .h, .hh, .hpp files in the SDK directory +file( + GLOB_RECURSE + SDK_CXX_FILES + "${SDK_DIR}/*.cc" + "${SDK_DIR}/*.c" + "${SDK_DIR}/*.cpp" + "${SDK_DIR}/*.h" + "${SDK_DIR}/*.hh" + "${SDK_DIR}/*.hpp") +option(CLANG_FORMAT_CHECK "Run clang-format in check mode" OFF) +message(STATUS "Clang format check: ${CLANG_FORMAT_CHECK}") + +list(FILTER SDK_CXX_FILES EXCLUDE REGEX "${SDK_DIR}/include/lebai/config.hh") + +# Create the clang-format target +if(CLANG_FORMAT_CHECK) + message(STATUS "Add custom target clang-format") + add_custom_target(clang-format ALL COMMAND clang-format -style=file --Werror + --dry-run ${SDK_CXX_FILES}) +else() + add_custom_target(clang-format COMMAND clang-format -style=file -i ${SDK_CXX_FILES}) +endif() find_package(Doxygen) -option(BUILD_DOCUMENTATION "Create and install the HTML based API documentation (requires Doxygen)" ON) +option(BUILD_DOCUMENTATION + "Create and install the HTML based API documentation (requires Doxygen)" + ON) if(BUILD_DOCUMENTATION AND DOXYGEN_FOUND) - if(NOT DOXYGEN_FOUND) - message(FATAL_ERROR "Doxygen is needed to build the documentation.") - endif() + if(NOT DOXYGEN_FOUND) + message(FATAL_ERROR "Doxygen is needed to build the documentation.") + endif() - set(doxyfile_in ${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile ) - set(doxyfile ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) + set(doxyfile_in ${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile) + set(doxyfile ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) - configure_file(${doxyfile_in} ${doxyfile} @ONLY) + configure_file(${doxyfile_in} ${doxyfile} @ONLY) - add_custom_target(doc ALL - COMMAND ${DOXYGEN_EXECUTABLE} ${doxyfile} - WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - COMMENT "Generating API documentation with Doxygen" - VERBATIM) + add_custom_target( + doc ALL + COMMAND ${DOXYGEN_EXECUTABLE} ${doxyfile} + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + COMMENT "Generating API documentation with Doxygen" + VERBATIM) - install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/html DESTINATION share/doc/${PROJECT_NAME}) + install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/html + DESTINATION share/doc/${PROJECT_NAME}) endif() - - - - diff --git a/Doxyfile b/Doxyfile index dfa7eb3..d91e50a 100644 --- a/Doxyfile +++ b/Doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "lebai sdk" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 1.1.24 +PROJECT_NUMBER = 1.1.25 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a @@ -885,7 +885,7 @@ EXCLUDE_PATTERNS = */cmake/* \ */python/* \ */sdk/python/* \ */sdk/src/* \ - */sdk/third/* \ + */third/* \ */sdk/test/* \ */examples/* diff --git a/cmake/cpp.cmake b/cmake/cpp.cmake index a7983b0..3efbbd8 100755 --- a/cmake/cpp.cmake +++ b/cmake/cpp.cmake @@ -6,70 +6,59 @@ enable_language(CXX) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) -configure_file("${PROJECT_SOURCE_DIR}/sdk/config.hh.in" "${PROJECT_SOURCE_DIR}/sdk/include/lebai/config.hh") +configure_file("${PROJECT_SOURCE_DIR}/sdk/config.hh.in" + "${PROJECT_SOURCE_DIR}/sdk/include/lebai/config.hh") include(GNUInstallDirs) add_subdirectory(sdk) # Install -install(EXPORT ${PROJECT_NAME}Targets +install( + EXPORT ${PROJECT_NAME}Targets NAMESPACE ${PROJECT_NAMESPACE}:: DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME} COMPONENT Devel) include(CMakePackageConfigHelpers) -configure_package_config_file(cmake/${PROJECT_NAME}Config.cmake.in +configure_package_config_file( + ${PROJECT_NAME}Config.cmake.in "${PROJECT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" INSTALL_DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" - NO_SET_AND_CHECK_MACRO - NO_CHECK_REQUIRED_COMPONENTS_MACRO) + NO_SET_AND_CHECK_MACRO NO_CHECK_REQUIRED_COMPONENTS_MACRO) write_basic_package_version_file( "${PROJECT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" COMPATIBILITY SameMajorVersion) install( - FILES - "${PROJECT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" - "${PROJECT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" + FILES "${PROJECT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" + "${PROJECT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" COMPONENT Devel) -# add_cpp_example() -# CMake function to generate and build C++ example. -# Parameters: -# the C++ filename -# e.g.: -# add_cpp_example(foo.cpp) +# add_cpp_example() CMake function to generate and build C++ example. +# Parameters: the C++ filename e.g.: add_cpp_example(foo.cpp) function(add_cpp_example FILE_NAME) message(STATUS "Configuring example ${FILE_NAME}: ...") get_filename_component(EXAMPLE_NAME ${FILE_NAME} NAME_WE) get_filename_component(COMPONENT_DIR ${FILE_NAME} DIRECTORY) get_filename_component(COMPONENT_NAME ${COMPONENT_DIR} NAME) - if(APPLE) - set(CMAKE_INSTALL_RPATH - "@loader_path/../${CMAKE_INSTALL_LIBDIR};@loader_path") - elseif(UNIX) + if(UNIX) set(CMAKE_INSTALL_RPATH "$ORIGIN/../${CMAKE_INSTALL_LIBDIR}:$ORIGIN") endif() add_executable(${EXAMPLE_NAME} ${FILE_NAME}) - target_include_directories(${EXAMPLE_NAME} - PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} - ${PROJECT_SOURCE_DIR}/sdk/src) + target_include_directories( + ${EXAMPLE_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} + ${PROJECT_SOURCE_DIR}/sdk/src) target_compile_features(${EXAMPLE_NAME} PRIVATE cxx_std_14) - target_link_libraries(${EXAMPLE_NAME} PRIVATE - ${PROJECT_NAMESPACE}::lebai-cpp) + target_link_libraries(${EXAMPLE_NAME} PRIVATE ${PROJECT_NAMESPACE}::lebai-cpp) if(UNIX) - target_link_libraries(${EXAMPLE_NAME} PRIVATE - pthread) + target_link_libraries(${EXAMPLE_NAME} PRIVATE pthread) endif() - # include(GNUInstallDirs) - # install(TARGETS ${EXAMPLE_NAME}) + # include(GNUInstallDirs) install(TARGETS ${EXAMPLE_NAME}) - # if(BUILD_TESTING) - # add_test(NAME cpp_${COMPONENT_NAME}_${EXAMPLE_NAME} COMMAND ${EXAMPLE_NAME}) - # endif() + # if(BUILD_TESTING) add_test(NAME cpp_${COMPONENT_NAME}_${EXAMPLE_NAME} + # COMMAND ${EXAMPLE_NAME}) endif() message(STATUS "Configuring example ${FILE_NAME}: ...DONE") endfunction() diff --git a/doc/changelog.md b/doc/changelog.md index ba3b61a..104683d 100644 --- a/doc/changelog.md +++ b/doc/changelog.md @@ -1,5 +1,8 @@ # ChangeLog +## 1.1.25 +优化代码格式和构建。 + ## 1.1.24 暂时移除windows上python3.12生成。 diff --git a/cmake/lebaiConfig.cmake.in b/lebaiConfig.cmake.in similarity index 100% rename from cmake/lebaiConfig.cmake.in rename to lebaiConfig.cmake.in diff --git a/sdk/CMakeLists.txt b/sdk/CMakeLists.txt index 453e4e7..d557cf2 100755 --- a/sdk/CMakeLists.txt +++ b/sdk/CMakeLists.txt @@ -15,7 +15,7 @@ target_sources(lebai-cpp target_include_directories(lebai-cpp PUBLIC $ - $ + $ $) target_compile_features(lebai-cpp PUBLIC cxx_std_14) if(WIN32) diff --git a/sdk/include/lebai/discovery.hh b/sdk/include/lebai/discovery.hh index 26664c8..e506692 100755 --- a/sdk/include/lebai/discovery.hh +++ b/sdk/include/lebai/discovery.hh @@ -1,18 +1,18 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once @@ -20,66 +20,63 @@ #include #include -namespace lebai -{ - namespace zeroconf - { +namespace lebai { +namespace zeroconf { +/** + * \brief Lebai机械臂控制器的信息数据结构. + * + */ +class ControllerInfo { + public: /** - * \brief Lebai机械臂控制器的信息数据结构. - * + * \brief 将控制器信息转换为字符串. + * + * \return 字符串. */ - class ControllerInfo - { - public: - /** - * \brief 将控制器信息转换为字符串. - * - * \return 字符串. - */ - std::string str(); + std::string str(); + + std::string hostname; /*!< 主机名字. */ + std::string ip_address; /*!< IP地址. */ + std::string mac_address; /*!< MAC地址. */ + std::string model; /*!< 机械臂模型. */ + std::string ds_version; /*!< ds软件版本. */ + std::string rc_version; /*!< rc软件版本. */ + std::string id; /*!< 机械臂产品ID. */ +}; - std::string hostname; /*!< 主机名字. */ - std::string ip_address; /*!< IP地址. */ - std::string mac_address; /*!< MAC地址. */ - std::string model; /*!< 机械臂模型. */ - std::string ds_version; /*!< ds软件版本. */ - std::string rc_version; /*!< rc软件版本. */ - std::string id; /*!< 机械臂产品ID. */ - }; - +/** + * @brief 自动发现局域网内lebai机械臂. + * + */ +class Discovery { + public: + /** + * @brief Discovery的内部实现. + * @note 用户无需使用. + */ + class DiscoveryImpl; /** - * @brief 自动发现局域网内lebai机械臂. + * @brief 构造Discovery对象. * */ - class Discovery - { - public: - /** - * @brief Discovery的内部实现. - * @note 用户无需使用. - */ - class DiscoveryImpl; - /** - * @brief 构造Discovery对象. - * - */ - Discovery(); - /** - * @brief 析构Discovery对象. - * - */ - virtual ~Discovery(); + Discovery(); + /** + * @brief 析构Discovery对象. + * + */ + virtual ~Discovery(); - /** - * @brief 获取局域网内lebai机械臂的信息数据,可以用来自动发现局域网内的所有机械臂控制器. - * - * @return std::vector 所有的机械臂的信息数据. - */ - std::vector resolve(); + /** + * @brief + * 获取局域网内lebai机械臂的信息数据,可以用来自动发现局域网内的所有机械臂控制器. + * + * @return std::vector 所有的机械臂的信息数据. + */ + std::vector resolve(); - protected: - std::unique_ptr impl_; /*!< 内部实现数据结构,用户无需关注. */ - }; - } + protected: + std::unique_ptr impl_; /*!< 内部实现数据结构,用户无需关注. */ +}; +} // namespace zeroconf -} // namespace lebai +} // namespace lebai diff --git a/sdk/include/lebai/lebai.hh b/sdk/include/lebai/lebai.hh index c32cca4..28b4594 100644 --- a/sdk/include/lebai/lebai.hh +++ b/sdk/include/lebai/lebai.hh @@ -2,19 +2,21 @@ /*! \mainpage lebai * [TOC] - * # 概述 - * Lebai机械臂All in one开发包。开发包通过C++实现和机械臂的通讯,提供和机械臂控制器交互的接口,并且通过[SWIG](https://www.swig.org/ "SWIG")生成其它各种语言的接口库. - * + * # 概述 + * Lebai机械臂All in + * one开发包。开发包通过C++实现和机械臂的通讯,提供和机械臂控制器交互的接口,并且通过[SWIG](https://www.swig.org/ + * "SWIG")生成其它各种语言的接口库. + * * 您可以通过项目的README文档来了解如何构建和安装本开发包. - * + * * 您也可以基于本开发包创建使用其它语言的开发包. - * + * * # 如何开始 * 查阅 \ref README.md "README" 文档,了解如何构建和安装本开发包. - * + * * # ChangeLog * 查阅 \ref doc/changelog.md. - * + * * # Python * 查看 \ref doc/python.md 来获取使用python开发相关的内容. * @@ -23,10 +25,9 @@ * * # Develop * 如果需要开发sdk,添加新的功能,可以参考 \ref doc/develop.md. - * - * # FAQ * + * + * # FAQ * * 参考 \ref doc/faq.md. - * - * + * + * */ - diff --git a/sdk/include/lebai/lua_robot.hh b/sdk/include/lebai/lua_robot.hh index bc502e2..ffcfbb0 100644 --- a/sdk/include/lebai/lua_robot.hh +++ b/sdk/include/lebai/lua_robot.hh @@ -1,103 +1,98 @@ /** * Copyright 2022-2023 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once #include #include #include -#include -#include -namespace lebai -{ - namespace l_master - { - +namespace lebai { +namespace l_master { + +/** + * @brief 机械臂的Lua接口,通过本对象向机械臂发送lua指令. + * + */ +class LuaRobot { + public: + /** + * @brief 内部实现. + * @note 用户无需关注. + */ + class LuaRobotImpl; + /** + * @brief 构造LuaRobot对象.可以通过该对象向机械臂发送lua指令,并且获取返回值。 + * + * 可以参考[Lua指令说明](http://help.lebai.ltd/dev/lua.html)了解所有和机械臂相关的lua指令 + * + * + * @param ip: 机械臂IP地址. + */ + explicit LuaRobot(std::string ip); + /** + * @brief 析构LuaRobot对象. + * + */ + virtual ~LuaRobot(); /** - * @brief 机械臂的Lua接口,通过本对象向机械臂发送lua指令. + * 示例代码: + * + * lua_robot.send("start_sys()"); + * + * @brief 向机械臂发送lua指令. + * @note 该函数只会发送lua指令给机械臂,不会读取机械臂的返回数据. + * + * @param lua_code: lua指令. + */ + void send(const std::string& lua_code); + /** + * 示例代码: + * + * std::vector codes; + * codes.push_back("start_sys()"); + * codes.push_back("movej({j1 = 1.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = + * 0}, 1.2, 0.2, 0, 0)"); codes.push_back("movej({j1 = 0.0, j2 = 0, j3 = 0, j4 + * = 0, j5 = 0, j6 = 0}, 1.2, 0.2, 0, 0)"); codes.push_back("sync()"); + * codes.push_back("stop_sys()"); + * lua_robot.send(codes); + * + * @brief 向机械臂发送多行lua指令.这些指令会按照顺序执行 + * @note 该函数只会发送lua指令给机械臂,不会读取机械臂的返回数据. + * + * @param lua_codes: 多个(行)lua指令. + */ + void send(const std::vector& lua_codes); + /** + * 示例代码: + * + * auto ret = lua_robot.call("get_robot_mode()"); + * + * @brief 向机械臂发送lua指令,并且获取机械臂的返回数据. + * @note 该函数会发送lua指令给机械臂,并且读取机械臂的返回数据. * + * @param lua_code: lua指令. + * @return std::string: 机械臂返回的数据. */ - class LuaRobot - { - public: - /** - * @brief 内部实现. - * @note 用户无需关注. - */ - class LuaRobotImpl; - /** - * @brief 构造LuaRobot对象.可以通过该对象向机械臂发送lua指令,并且获取返回值。 - * - * 可以参考[Lua指令说明](http://help.lebai.ltd/dev/lua.html)了解所有和机械臂相关的lua指令 - * - * - * @param ip: 机械臂IP地址. - */ - explicit LuaRobot(std::string ip); - /** - * @brief 析构LuaRobot对象. - * - */ - virtual ~LuaRobot(); - /** - * 示例代码: - * - * lua_robot.send("start_sys()"); - * - * @brief 向机械臂发送lua指令. - * @note 该函数只会发送lua指令给机械臂,不会读取机械臂的返回数据. - * - * @param lua_code: lua指令. - */ - void send(const std::string & lua_code); - /** - * 示例代码: - * - * std::vector codes; - * codes.push_back("start_sys()"); - * codes.push_back("movej({j1 = 1.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = 0}, 1.2, 0.2, 0, 0)"); - * codes.push_back("movej({j1 = 0.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = 0}, 1.2, 0.2, 0, 0)"); - * codes.push_back("sync()"); - * codes.push_back("stop_sys()"); - * lua_robot.send(codes); - * - * @brief 向机械臂发送多行lua指令.这些指令会按照顺序执行 - * @note 该函数只会发送lua指令给机械臂,不会读取机械臂的返回数据. - * - * @param lua_codes: 多个(行)lua指令. - */ - void send(const std::vector & lua_codes); - /** - * 示例代码: - * - * auto ret = lua_robot.call("get_robot_mode()"); - * - * @brief 向机械臂发送lua指令,并且获取机械臂的返回数据. - * @note 该函数会发送lua指令给机械臂,并且读取机械臂的返回数据. - * - * @param lua_code: lua指令. - * @return std::string: 机械臂返回的数据. - */ - std::string call(const std::string & lua_code); - /** @}*/ - protected: - std::unique_ptr impl_; /*!< 内部实现数据结构,用户无需关注. */ - }; + std::string call(const std::string& lua_code); + /** @}*/ + protected: + std::unique_ptr impl_; /*!< 内部实现数据结构,用户无需关注. */ +}; - } +} // namespace l_master -} // namespace l_master_sdk +} // namespace lebai diff --git a/sdk/include/lebai/robot.hh b/sdk/include/lebai/robot.hh index f0fafdb..584328d 100644 --- a/sdk/include/lebai/robot.hh +++ b/sdk/include/lebai/robot.hh @@ -1,18 +1,18 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once @@ -22,1059 +22,1156 @@ #include #include -namespace lebai -{ - namespace l_master - { +namespace lebai { +namespace l_master { +/** + * @brief 获取当前SDK版本号 + * + * @return 返回版本号字符串 + */ +std::string version(); +/** + * @brief CartesianPose是用来表示空间位姿的数据结构. + * 数据为字典数据,其中应当包括键为x,y,z,rz,ry,rx的数据. + * + */ +using CartesianPose = std::map; +using DoubleVector = std::vector; +/** + * @brief 运动学正解的返回值数据结构. + * + */ +struct KinematicsForwardResp { + CartesianPose + pose; /*!< + 笛卡尔坐标位置,map数据,应当包括'x','y','z','rx','ry','rz'的键值. + */ + bool ok = false; /*!< 计算是否成功. */ +}; +/** + * @brief 运动学逆解的返回值数据结构 + * + */ +struct KinematicsInverseResp { + DoubleVector + joint_positions; /*!< + 机械臂关节位置的map数据,应当包括'j1','j2','j3','j4','j5','j6'六个关节的角度值. + */ + bool ok = false; /*!< 计算是否成功 */ +}; +/*** + * @brief 夹爪数据结构. + * + */ +struct ClawData { + double force; /*!< 夹爪的力矩值. */ + double amplitude; /*!< 夹爪的开合角度值. */ + bool hold_on; /*!< 夹爪是否夹住. */ +}; + +/** + * @brief 机械臂的主要接口对象,通过本对象的方法与机械臂进行数据交互. + * @note 使用该数据结构和机械臂交互要求机械臂软件版本>=3.1.5。 + * @note 接口的每一个函数都可能抛出异常std::runtime_error, + * 这是因为网络连接丢失或者调用的逻辑错误等。 + * + * + */ +class Robot { + public: /** - * @brief 获取当前SDK版本号 - * - * @return 返回版本号字符串 + * @brief 内部实现. + * @note 用户无需使用. + * */ - std::string version(); + class RobotImpl; + /** - * @brief CartesianPose是用来表示空间位姿的数据结构. - * 数据为字典数据,其中应当包括键为x,y,z,rz,ry,rx的数据. - * + * @brief 构造Robot对象. + * @note + * 当你尝试创建Robot对象时,会根据传入的ip参数尝试去连接机械臂,但是可能会连接失败,当连接不成功时,对象依然会创建。 + * + * + * @param ip: 机械臂IP地址. + * @param simulator: + * 用于表示机械臂是否为仿真机械臂(docker仿真或控制器运行在仿真模式下)的macs标志.True表示仿真模式,False表示实物机械臂. */ - using CartesianPose = std::map; - using DoubleVector = std::vector; + explicit Robot(std::string ip, bool simulator = false); /** - * @brief 运动学正解的返回值数据结构. - * + * @brief 析构Robot对象. + * */ - struct KinematicsForwardResp - { - CartesianPose pose; /*!< 笛卡尔坐标位置,map数据,应当包括'x','y','z','rx','ry','rz'的键值. */ - bool ok = false; /*!< 计算是否成功. */ - }; + virtual ~Robot(); /** - * @brief 运动学逆解的返回值数据结构 - * + * 示例代码: + * + * std::string movej_req = + * "{\"param\":{\"v\":0.1},\"pose\":{\"joint\":{\"delta\":"{\"joint\":[-1.0,0.0,0.0,0.0,0.0,0.0]}}}}"; + * resp = robot.call("movej", movej_req); + * std::cout << "resp: " << std::get<0>(resp) << ", " << std::get<1>(resp) + * << std::endl; + * + * + * @brief 用JSON格式字符串调用机械臂的接口. + * @note SDK采用JSONRPC协议和机械臂控制进行通讯. + * 您可以自行生成JSON数据,并通过本接口调用相应的JSONRPC,并获取返回的结果和JSON数据. + * @param[in] method 方法名字 + * @param[in] params 请求JSONRPC的JSON格式字符串. + * @return 返回一个元组,第一个元素是返回码,第二个元素是数据字符串. + * 如果返回码为0,表示调用成功,第二个元素是JSONRPC的返回数据. + * 如果返回码为非0,表示调用失败,第二个元素是错误信息. */ - struct KinematicsInverseResp - { - DoubleVector joint_positions; /*!< 机械臂关节位置的map数据,应当包括'j1','j2','j3','j4','j5','j6'六个关节的角度值. */ - bool ok = false; /*!< 计算是否成功 */ - }; - - struct ClawData - { - double force; - double amplitude; - bool hold_on; - }; + std::tuple call(const std::string &method, + const std::string ¶ms); + /** + * @brief + * 返回是否和机械臂的网络连接正常,如果网络连接异常,调用和机械臂交互的接口会抛出异常std::runtime_error。 + * @note 不建议使用,直接catch接口调用获取网络异常。 + * @return true 表示网络连接正常,false表示网络连接异常. + */ + bool is_network_connected(); + /** \defgroup STARTSTOP 启动停止. + * \brief 启动停止相关的接口. + */ - /** - * @brief 机械臂的主要接口对象,通过本对象的方法与机械臂进行数据交互. - * @note 使用该数据结构和机械臂交互要求机械臂软件版本>=3.1.5。 - * @note 接口的每一个函数都可能抛出异常std::runtime_error, 这是因为网络连接丢失或者调用的逻辑错误等。 - * - * - */ - class Robot - { - public: - /** - * @brief 内部实现. - * @note 用户无需使用. - * - */ - class RobotImpl; + /** \defgroup CONFIG 机器人配置. + * \brief 机器人配置参数相关的接口. + */ + /** \defgroup MOTION 机械臂运动. + * \brief 机械臂运动相关的接口. + */ + /** \defgroup STATUS 机械臂状态. + * \brief 机械臂状态相关的接口. + */ - /** - * @brief 构造Robot对象. - * @note 当你尝试创建Robot对象时,会根据传入的ip参数尝试去连接机械臂,但是可能会连接失败,当连接不成功时,对象依然会创建。 - * - * - * @param ip: 机械臂IP地址. - * @param simulator: 用于表示机械臂是否为仿真机械臂(docker仿真或控制器运行在仿真模式下)的macs标志.True表示仿真模式,False表示实物机械臂. - */ - explicit Robot(std::string ip, bool simulator = false); - /** - * @brief 析构Robot对象. - * - */ - virtual ~Robot(); - /** - * 示例代码: - * - * std::string movej_req = "{\"param\":{\"v\":0.1},\"pose\":{\"joint\":{\"delta\":"{\"joint\":[-1.0,0.0,0.0,0.0,0.0,0.0]}}}}"; - * resp = robot.call("movej", movej_req); - * std::cout << "resp: " << std::get<0>(resp) << ", " << std::get<1>(resp) << std::endl; - * - * - * @brief 用JSON格式字符串调用机械臂的接口. - * @note SDK采用JSONRPC协议和机械臂控制进行通讯. 您可以自行生成JSON数据,并通过本接口调用相应的JSONRPC,并获取返回的结果和JSON数据. - * @param[in] method 方法名字 - * @param[in] params 请求JSONRPC的JSON格式字符串. - * @return 返回一个元组,第一个元素是返回码,第二个元素是数据字符串. - * 如果返回码为0,表示调用成功,第二个元素是JSONRPC的返回数据. - * 如果返回码为非0,表示调用失败,第二个元素是错误信息. - */ - std::tuple call(const std::string & method, const std::string & params); - - /** - * @brief 返回是否和机械臂的网络连接正常,如果网络连接异常,调用和机械臂交互的接口会抛出异常std::runtime_error。 - * @note 不建议使用,直接catch接口调用获取网络异常。 - * @return true 表示网络连接正常,false表示网络连接异常. - */ - bool is_network_connected(); - - /** \defgroup STARTSTOP 启动停止. - * \brief 启动停止相关的接口. - */ + /** \addtogroup IO 通用输入输出 + * \brief 通用输入输出相关的接口 + */ - /** \defgroup CONFIG 机器人配置. - * \brief 机器人配置参数相关的接口. - */ + /** \defgroup CLAW 夹爪. + * \brief 夹爪相关的接口. + */ - /** \defgroup MOTION 机械臂运动. - * \brief 机械臂运动相关的接口. - */ + /** \defgroup LED 灯板. + * \brief 灯板相关的接口. + */ - /** \defgroup STATUS 机械臂状态. - * \brief 机械臂状态相关的接口. - */ - - /** \addtogroup IO 通用输入输出 - * \brief 通用输入输出相关的接口 - */ + /** \defgroup SIGNAL 信号量. + * \brief 信号量相关的接口. + */ - /** \defgroup CLAW 夹爪. - * \brief 夹爪相关的接口. - */ + /** \defgroup PROGRAM 程序控制. + * \brief 程序控制相关的接口. + */ - /** \defgroup LED 灯板. - * \brief 灯板相关的接口. - */ + /** \defgroup ROBOTICS 机器人. + * \brief 机器人计算相关的接口. + */ - /** \defgroup SIGNAL 信号量. - * \brief 信号量相关的接口. - */ + /** \defgroup FILE 文件系统. + * \brief 文件系统相关的接口. + */ - /** \defgroup PROGRAM 程序控制. - * \brief 程序控制相关的接口. - */ + /** \defgroup MODBUS modbus. + * \brief modbus相关的接口. + */ - /** \defgroup ROBOTICS 机器人. - * \brief 机器人计算相关的接口. - */ + /** \defgroup SCENE 场景. + * \brief 场景相关的接口. + */ - /** \defgroup FILE 文件系统. - * \brief 文件系统相关的接口. - */ - - /** \defgroup MODBUS modbus. - * \brief modbus相关的接口. - */ + /** \defgroup SERIAL serial. + * \brief 串口相关的接口. + */ - /** \defgroup SCENE 场景. - * \brief 场景相关的接口. - */ + /** \addtogroup STARTSTOP + * @{ + */ - /** \defgroup SERIAL serial. - * \brief 串口相关的接口. - */ + /** + * @brief 启动机械臂(机械臂上使能). + * + */ + void start_sys(); + /** + * @brief 停止机械臂(机械臂下使能). + * + */ - /** \addtogroup STARTSTOP - * @{ - */ - - /** - * @brief 启动机械臂(机械臂上使能). - * - */ - void start_sys(); - /** - * @brief 停止机械臂(机械臂下使能). - * - */ + void stop_sys(); + /** + * @brief 关闭机器人电源(关机). + * + */ + void powerdown(); + /** + * @brief 停止运动(但不下电). + * + */ + void stop(); + /** + * @brief 紧急停止(急停). + * + */ + void estop(); + /** + * @brief 进入示教模式. + * + */ + void teach_mode(); + /** + * @brief 退出示教模式. + * + */ + void end_teach_mode(); + /** + * @brief 暂停运动. + * + */ + void pause(); + /** + * @brief 恢复运动. + * + */ + void resume(); + /** + * @brief 重新启动机箱 + */ + void reboot(); + /** @}*/ - void stop_sys(); - /** - * @brief 关闭机器人电源(关机). - * - */ - void powerdown(); - /** - * @brief 停止运动(但不下电). - * - */ - void stop(); - /** - * @brief 紧急停止(急停). - * - */ - void estop(); - /** - * @brief 进入示教模式. - * - */ - void teach_mode(); - /** - * @brief 退出示教模式. - * - */ - void end_teach_mode(); - /** - * @brief 暂停运动. - * - */ - void pause(); - /** - * @brief 恢复运动. - * - */ - void resume(); - /** - * @brief 重新启动机箱 - */ - void reboot(); - /** @}*/ + /** \addtogroup MOTION + * @{ + */ + /** + * 示例代码: + * + * std::vector joint_positions = {0.0, -60.0 / 180.0 * M_PI, 80.0 + * / 180.0 * M_PI, -10.0 / 180.0 * M_PI, -60.0 / 180.0 * M_PI, 0.0}; + * robot.movej(joint_positions, 3.0, 1.0, 0.0, 0.0); + * + * + * @brief 通过关节位置发送机械臂关节移动 + * @note + * 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. + * @param[in] joint_positions 目标位置的关节数据,为关节的角度值构成的数组. + * @param[in] a 加速度 + * @param[in] v 速度 + * @param[in] t + * 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. + * @param[in] r 交融半径,设置为0,则无交融半径. + * @return >0 发送成功 + * @return <=0 发送失败 + * + */ + int movej(const std::vector &joint_positions, double a, double v, + double t, double r); + /** + * 示例代码: + * + * robot.movej({”x",-0.296},{"y",-0.295},{"z",0.285},{"rz",60.0 / 180.0 * + * M_PI},{"ry",-5.0 / 180.0 * M_PI},{"rx", 81.0 / 180.0 * M_PI}}, 3.0, 1.0, + * 0.0, 0.0); + * + * + * @brief 通过坐标位置发送机械臂关节移动 + * @note + * 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. + * @param[in] cart_pose + * 目标位置在机器人基座标系下的坐标数据(目前不支持在其它坐标系下的坐标数据),CartesianPose + * = std::map,应当包括键为x,y,z,rz,ry,rx的值. + * @param[in] a 加速度. + * @param[in] v 速度. + * @param[in] t + * 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. + * @param[in] r 交融半径,设置为0,则无交融半径. + * @return >0 发送成功 + * @return <=0 发送失败 + */ + int movej(const CartesianPose &cart_pose, double a, double v, double t, + double r); + /** + * 示例代码: + * + * std::vector joint_positions = {0.0, -60.0 / 180.0 * M_PI, 80.0 + * / 180.0 * M_PI, -10.0 / 180.0 * M_PI, -60.0 / 180.0 * M_PI, 0.0}; + * robot.movel(joint_positions, 3.0, 1.0, 0.0, 0.0); + * + * + * @brief 通过关节位置发送机械臂直线移动 + * @note + * 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. + * @param[in] joint_positions: 目标位置的关节数据,为关节的角度值构成的数组. + * @param[in] a 加速度. + * @param[in] v 速度. + * @param[in] t + * 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. + * @param[in] r 交融半径,设置为0,则无交融半径. + * @return >0 发送成功 + * @return <=0 发送失败 + */ + int movel(const std::vector &joint_positions, double a, double v, + double t, double r); + /** + * 示例代码: + * + * robot.movel({”x",-0.296},{"y",-0.295},{"z",0.285},{"rz",60.0 / 180.0 * + * M_PI},{"ry",-5.0 / 180.0 * M_PI},{"rx", 81.0 / 180.0 * M_PI}}, 3.0, 1.0, + * 0.0, 0.0); + * + * + * @brief 通过坐标位置发送机械臂直线移动 + * @note + * 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. + * @param cart_pose + * 目标位置在机器人基座标系下的坐标数据(目前不支持在其它坐标系下的坐标数据),CartesianPose + * = std::map,应当包括键为x,y,z,rz,ry,rx的值. + * @param a 加速度. + * @param v 速度. + * @param t + * 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. + * @param r 交融半径,设置为0,则无交融半径. + * @return >0 发送成功. + * @return <=0 发送失败. + */ + int movel(const CartesianPose &cart_pose, double a, double v, double t, + double r); + /** + * 示例代码 + * + * robot.movec({3.0/ 180.0 * M_PI, -48.0/ 180.0 * M_PI, 78.0/ 180.0 * + * M_PI, 9.0/ 180.0 * M_PI, -67.0/ 180.0 * M_PI, -3.0/ 180.0 * M_PI}, + * {-28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ + * 180.0 * M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI}, 0.0, 1.0, 0.5, 0.0, + * 0.0); + * + * @brief 通过关节位置发送机械臂圆弧运动. + * @param[in] joint_via + * 圆弧上途径点关节位置,为关节的角度值构成的数组.为圆上三点中的一点. + * @param[in] joint + * 圆弧目标点关节位置,为关节的角度值构成的数组.如果编程rad不为零,则为圆上三点中的一点. + * @param[in] rad + * 圆弧角度值,单位为弧度,如果为零,则走到目标点,正负值用来确定圆弧方向. + * @param[in] a 加速度. + * @param[in] v 速度. + * @param[in] t: + * 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. + * @param[in] r: 交融半径,设置为0,则无交融半径. + * @return >0 发送成功. + * @return <=0 发送失败. + */ + int movec(const std::vector &joint_via, + const std::vector &joint, double rad, double a, double v, + double t, double r); + /** + * + * @brief 通过坐标位置发送机械臂圆弧运动 + * @param[in] cart_via + * 圆弧上途径点坐标位置,应当包括键为x,y,z,rz,ry,rx的值.为圆上三点中的一点. + * @param[in] cart + * 圆弧目标点坐标位置,应当包括键为x,y,z,rz,ry,rx的值.如果编程rad不为零,则为圆上三点中的一点. + * @param[in] rad + * 圆弧角度值,单位为弧度,如果为零,则走到目标点,正负值用来确定圆弧方向. + * @param[in] a 加速度. + * @param[in] v 速度. + * @param[in] t: + * 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. + * @param[in] r: 交融半径,设置为0,则无交融半径. + * @return >0 发送成功. + * @return <=0 发送失败. + */ + int movec(const CartesianPose &cart_via, const CartesianPose &cart, + double rad, double a, double v, double t, double r); + /** + * 示例代码: + * + * robot.speedj( 1.0, {0.5,0.0,0.0,0.0,0.0,0.0}, 0.0); + * + * @brief 通过关节速度矢量发送机械臂关节匀速运动 + * @param[in] a 加速度. + * @param[in] v 速度矢量 + * @param[in] t: 运动时间,默认t = 0,一直运动到限位. + * @return >0 发送成功.返回运动号 + * @return <=0 发送失败. + */ + int speedj(double a, const std::vector &v, double t = 0.0); + /** + * + * 示例代码: + * + * robot.speedl( 1.0, {{"x", 0.0}, {"y", 0.0}, {"z", 0.1}, {"rx", 0.0}, + * {"ry", 0.0}, {"rz", 0.0}}, 0.0); + * + * @brief 通过坐标速度矢量发送机械臂关节匀速运动 + * @param[in] a 加速度. + * @param[in] v 速度矢量 + * @param[in] t: 运动时间,默认t = 0,一直运动到限位. + * @param[in] reference: 参考坐标系,默认为零. + * @return >0 发送成功.返回运动号 + * @return <=0 发送失败. + */ + int speedl(double a, const CartesianPose &v, double t = 0.0, + const CartesianPose &reference = {{"x", 0.0}, + {"y", 0.0}, + {"z", 0.0}, + {"rx", 0.0}, + {"ry", 0.0}, + {"rz", 0.0}}); + /** + * 示例代码: + * + * std::vector joint_positions = {0.0, -60.0 / 180.0 * M_PI, 80.0 + * / 180.0 * M_PI, -10.0 / 180.0 * M_PI, -60.0 / 180.0 * M_PI, 0.0}; + * robot.toawrdj(joint_positions, 3.0, 1.0, 0.0, 0.0); + * + * + * @brief 通过关节位置发送机械臂关节自由移动. + * @note + * 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节自由移动即返回,不会等待运动结束. + * @param[in] joint_positions: 目标位置的关节数据,为关节的角度值构成的数组. + * @param[in] a: 加速度. + * @param[in] v: 速度. + * @param[in] t: + * 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. + * @param[in] r: 交融半径,设置为0,则无交融半径. + * @return >0 发送成功.返回运动号 + * @return <=0 发送失败. + * + */ + int towardj(const std::vector &joint_positions, double a, double v, + double t, double r); + /** + * @brief 伺服运动PVAT + * + * @param p 关节位置,或者坐标位置(将通过运动学反解转为关节位置). + * @param v 每个关节的速度 (rad/s)。如该值为数字,则表示所有关节速度相同. + * @param a 每个关节的加速度 (rad/s2)。如该值为数字,则表示所有关节加速度相同. + * @param t 运动时间 (s) + */ + void move_pvat(std::vector p, std::vector v, + std::vector a, double t); + /** + * @brief 等待运动完成. + * + * @param id 指定运动的id(0为等待全部任务). + */ + void wait_move(unsigned int id); + /** + * @brief 等待所有运动完成. + * + */ + void wait_move(); + /** + * @brief 查询当前正在运动的MotionId(无运动时返回上次MotionId). + */ + unsigned int get_running_motion(); + /** + * @brief 查询指定MotionId的运动状态. + * + * @return id 指定的运动id. + */ + std::string get_motion_state(unsigned int id); + /** + * @brief 停止所有运动. + */ + void stop_move(); + /** @}*/ - /** \addtogroup MOTION - * @{ - */ + /** \addtogroup STATUS + * @{ + */ - /** - * 示例代码: - * - * std::vector joint_positions = {0.0, -60.0 / 180.0 * M_PI, 80.0 / 180.0 * M_PI, -10.0 / 180.0 * M_PI, -60.0 / 180.0 * M_PI, 0.0}; - * robot.movej(joint_positions, 3.0, 1.0, 0.0, 0.0); - * - * - * @brief 通过关节位置发送机械臂关节移动 - * @note 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. - * @param[in] joint_positions 目标位置的关节数据,为关节的角度值构成的数组. - * @param[in] a 加速度 - * @param[in] v 速度 - * @param[in] t 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. - * @param[in] r 交融半径,设置为0,则无交融半径. - * @return >0 发送成功 - * @return <=0 发送失败 - * - */ - int movej(const std::vector & joint_positions, double a, double v, double t, double r); - /** - * 示例代码: - * - * robot.movej({”x",-0.296},{"y",-0.295},{"z",0.285},{"rz",60.0 / 180.0 * M_PI},{"ry",-5.0 / 180.0 * M_PI},{"rx", 81.0 / 180.0 * M_PI}}, 3.0, 1.0, 0.0, 0.0); - * - * - * @brief 通过坐标位置发送机械臂关节移动 - * @note 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. - * @param[in] cart_pose 目标位置在机器人基座标系下的坐标数据(目前不支持在其它坐标系下的坐标数据),CartesianPose = std::map,应当包括键为x,y,z,rz,ry,rx的值. - * @param[in] a 加速度. - * @param[in] v 速度. - * @param[in] t 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. - * @param[in] r 交融半径,设置为0,则无交融半径. - * @return >0 发送成功 - * @return <=0 发送失败 - */ - int movej(const CartesianPose & cart_pose, double a, double v, double t, double r); - /** - * 示例代码: - * - * std::vector joint_positions = {0.0, -60.0 / 180.0 * M_PI, 80.0 / 180.0 * M_PI, -10.0 / 180.0 * M_PI, -60.0 / 180.0 * M_PI, 0.0}; - * robot.movel(joint_positions, 3.0, 1.0, 0.0, 0.0); - * - * - * @brief 通过关节位置发送机械臂直线移动 - * @note 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. - * @param[in] joint_positions: 目标位置的关节数据,为关节的角度值构成的数组. - * @param[in] a 加速度. - * @param[in] v 速度. - * @param[in] t 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. - * @param[in] r 交融半径,设置为0,则无交融半径. - * @return >0 发送成功 - * @return <=0 发送失败 - */ - int movel(const std::vector & joint_positions, double a, double v, double t, double r); - /** - * 示例代码: - * - * robot.movel({”x",-0.296},{"y",-0.295},{"z",0.285},{"rz",60.0 / 180.0 * M_PI},{"ry",-5.0 / 180.0 * M_PI},{"rx", 81.0 / 180.0 * M_PI}}, 3.0, 1.0, 0.0, 0.0); - * - * - * @brief 通过坐标位置发送机械臂直线移动 - * @note 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节移动即返回,不会等待运动结束. - * @param cart_pose 目标位置在机器人基座标系下的坐标数据(目前不支持在其它坐标系下的坐标数据),CartesianPose = std::map,应当包括键为x,y,z,rz,ry,rx的值. - * @param a 加速度. - * @param v 速度. - * @param t 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. - * @param r 交融半径,设置为0,则无交融半径. - * @return >0 发送成功. - * @return <=0 发送失败. - */ - int movel(const CartesianPose & cart_pose, double a, double v, double t, double r); - /** - * 示例代码 - * - * robot.movec({3.0/ 180.0 * M_PI, -48.0/ 180.0 * M_PI, 78.0/ 180.0 * M_PI, 9.0/ 180.0 * M_PI, -67.0/ 180.0 * M_PI, -3.0/ 180.0 * M_PI}, - * {-28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 * M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI}, - * 0.0, 1.0, 0.5, 0.0, 0.0); - * - * @brief 通过关节位置发送机械臂圆弧运动. - * @param[in] joint_via 圆弧上途径点关节位置,为关节的角度值构成的数组.为圆上三点中的一点. - * @param[in] joint 圆弧目标点关节位置,为关节的角度值构成的数组.如果编程rad不为零,则为圆上三点中的一点. - * @param[in] rad 圆弧角度值,单位为弧度,如果为零,则走到目标点,正负值用来确定圆弧方向. - * @param[in] a 加速度. - * @param[in] v 速度. - * @param[in] t: 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. - * @param[in] r: 交融半径,设置为0,则无交融半径. - * @return >0 发送成功. - * @return <=0 发送失败. - */ - int movec(const std::vector & joint_via, const std::vector & joint, double rad, double a, double v, double t, double r); - /** - * - * @brief 通过坐标位置发送机械臂圆弧运动 - * @param[in] cart_via 圆弧上途径点坐标位置,应当包括键为x,y,z,rz,ry,rx的值.为圆上三点中的一点. - * @param[in] cart 圆弧目标点坐标位置,应当包括键为x,y,z,rz,ry,rx的值.如果编程rad不为零,则为圆上三点中的一点. - * @param[in] rad 圆弧角度值,单位为弧度,如果为零,则走到目标点,正负值用来确定圆弧方向. - * @param[in] a 加速度. - * @param[in] v 速度. - * @param[in] t: 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. - * @param[in] r: 交融半径,设置为0,则无交融半径. - * @return >0 发送成功. - * @return <=0 发送失败. - */ - int movec(const CartesianPose & cart_via, const CartesianPose & cart, double rad, double a, double v, double t, double r); - /** - * 示例代码: - * - * robot.speedj( 1.0, {0.5,0.0,0.0,0.0,0.0,0.0}, 0.0); - * - * @brief 通过关节速度矢量发送机械臂关节匀速运动 - * @param[in] a 加速度. - * @param[in] v 速度矢量 - * @param[in] t: 运动时间,默认t = 0,一直运动到限位. - * @return >0 发送成功.返回运动号 - * @return <=0 发送失败. - */ - int speedj(double a, const std::vector & v, double t = 0.0); - /** - * - * 示例代码: - * - * robot.speedl( 1.0, {{"x", 0.0}, {"y", 0.0}, {"z", 0.1}, {"rx", 0.0}, {"ry", 0.0}, {"rz", 0.0}}, 0.0); - * - * @brief 通过坐标速度矢量发送机械臂关节匀速运动 - * @param[in] a 加速度. - * @param[in] v 速度矢量 - * @param[in] t: 运动时间,默认t = 0,一直运动到限位. - * @param[in] reference: 参考坐标系,默认为零. - * @return >0 发送成功.返回运动号 - * @return <=0 发送失败. - */ - int speedl(double a, const CartesianPose & v, double t = 0.0, const CartesianPose & reference = {{"x", 0.0}, {"y", 0.0}, {"z", 0.0}, {"rx", 0.0}, {"ry", 0.0}, {"rz", 0.0}}); - /** - * 示例代码: - * - * std::vector joint_positions = {0.0, -60.0 / 180.0 * M_PI, 80.0 / 180.0 * M_PI, -10.0 / 180.0 * M_PI, -60.0 / 180.0 * M_PI, 0.0}; - * robot.toawrdj(joint_positions, 3.0, 1.0, 0.0, 0.0); - * - * - * @brief 通过关节位置发送机械臂关节自由移动. - * @note 该接口为异步接口,仅向控制器内部的运动缓冲区写入一个关节自由移动即返回,不会等待运动结束. - * @param[in] joint_positions: 目标位置的关节数据,为关节的角度值构成的数组. - * @param[in] a: 加速度. - * @param[in] v: 速度. - * @param[in] t: 时间参数,如果设置时间不为零,则按照时间计算出速度,而不使用速度参数. - * @param[in] r: 交融半径,设置为0,则无交融半径. - * @return >0 发送成功.返回运动号 - * @return <=0 发送失败. - * - */ - int towardj(const std::vector & joint_positions, double a, double v, double t, double r); - /** - * @brief 伺服运动PVAT - * - * @param p 关节位置,或者坐标位置(将通过运动学反解转为关节位置). - * @param v 每个关节的速度 (rad/s)。如该值为数字,则表示所有关节速度相同. - * @param a 每个关节的加速度 (rad/s2)。如该值为数字,则表示所有关节加速度相同. - * @param t 运动时间 (s) - */ - void move_pvat(std::vector p, std::vector v, std::vector a, double t); - /** - * @brief 等待运动完成. - * - * @param id 指定运动的id(0为等待全部任务). - */ - void wait_move(unsigned int id); - /** - * @brief 等待所有运动完成. - * - */ - void wait_move(); - /** - * @brief 查询当前正在运动的MotionId(无运动时返回上次MotionId). - */ - unsigned int get_running_motion(); - /** - * @brief 查询指定MotionId的运动状态. - * - * @return id 指定的运动id. - */ - std::string get_motion_state(unsigned int id); - /** - * @brief 停止所有运动. - */ - void stop_move(); - /** @}*/ + /** + * @brief 获取机器人状态码 + * + * @return int 返回状态码. + * + * 状态码 | 状态 | 说明 + * ------ | ------------- | ------------- + * -1 | 控制系统故障 | 机器人软件控制系统异常 + * 0 | 硬件通讯故障 | 机器人硬件通讯故障 + * 1 | 已急停 | 机器人处于急停状态,请确认安全性 + * 2 | 初始化中 | 机器人初始化中 + * 4 | 初始化完成 | 机器人电源已开启 + * 5 | 空闲 | 机器人处于空闲状态 + * 6 | 暂停 | 机器人处于暂停中状态 + * 7 | 运行中 | 机器人运行中 + * 8 | 更新中 | 机器人系统更新中 + * 9 | 启动中 | 机器人初始化完成到空闲的启动过程中 + * 10 | 正在停止 | 机器人空闲状态转到停止状态 + * 11 | 示教中 | 机器人处于示教模式中 + * 12 | 已停止 | 机器人处于停止状态,非急停状态 + * + * @note 查看 具体信息. + */ + int get_robot_mode(); + /** + * @brief 查看急停原因 + * + * @return 急停原因 + */ + int get_estop_reason(); + /** + * @brief 是否已与手臂断开连接 + * + * @return 是否已断开连接 + */ + bool is_disconnected(); + /** + * @brief 手臂是否已下电 + * + * @return 是否已下电 + */ + bool is_down(); + /** + * @brief 获取机械臂关节当前反馈位置 + * + * @return 关节反馈位置数组,包括所有关节的角度值. + */ + std::vector get_actual_joint_positions(); + /** + * @brief 获取机械臂关节当前控制位置 + * + * @return 关节控制位置数组,包括所有关节的角度值. + */ + std::vector get_target_joint_positions(); + /** + * @brief 获取机械臂关节当前反馈速度 + * + * @return 关节反馈速度数据 + */ + std::vector get_actual_joint_speed(); + // get_target_joint_speed + /** + * @brief 获取机械臂关节当前控制力矩 + * + * @return 关节控制速度数据 + */ + std::vector get_target_joint_speed(); + /** + * @brief 获取机械臂末端在机械臂基坐标系下的实际位姿,CartesianPose = + * std::map,应当包括键为x,y,z,rz,ry,rx的值. + * + * @return CartesianPose + */ + CartesianPose get_actual_tcp_pose(); + /** + * @brief 获取机械臂末端在机械臂基坐标系下的控制位姿,CartesianPose = + * std::map,应当包括键为x,y,z,rz,ry,rx的值. + * + * @return CartesianPose + */ + CartesianPose get_target_tcp_pose(); - /** \addtogroup STATUS - * @{ - */ - - /** - * @brief 获取机器人状态码 - * - * @return int 返回状态码. - * - * 状态码 | 状态 | 说明 - * ------ | ------------- | ------------- - * -1 | 控制系统故障 | 机器人软件控制系统异常 - * 0 | 硬件通讯故障 | 机器人硬件通讯故障 - * 1 | 已急停 | 机器人处于急停状态,请确认安全性 - * 2 | 初始化中 | 机器人初始化中 - * 4 | 初始化完成 | 机器人电源已开启 - * 5 | 空闲 | 机器人处于空闲状态 - * 6 | 暂停 | 机器人处于暂停中状态 - * 7 | 运行中 | 机器人运行中 - * 8 | 更新中 | 机器人系统更新中 - * 9 | 启动中 | 机器人初始化完成到空闲的启动过程中 - * 10 | 正在停止 | 机器人空闲状态转到停止状态 - * 11 | 示教中 | 机器人处于示教模式中 - * 12 | 已停止 | 机器人处于停止状态,非急停状态 - * - * @note 查看 具体信息. - */ - int get_robot_mode(); - /** - * @brief 查看急停原因 - * - * @return 急停原因 - */ - int get_estop_reason(); - /** - * @brief 是否已与手臂断开连接 - * - * @return 是否已断开连接 - */ - bool is_disconnected(); - /** - * @brief 手臂是否已下电 - * - * @return 是否已下电 - */ - bool is_down(); - /** - * @brief 获取机械臂关节当前反馈位置 - * - * @return 关节反馈位置数组,包括所有关节的角度值. - */ - std::vector get_actual_joint_positions(); - /** - * @brief 获取机械臂关节当前控制位置 - * - * @return 关节控制位置数组,包括所有关节的角度值. - */ - std::vector get_target_joint_positions(); - /** - * @brief 获取机械臂关节当前反馈速度 - * - * @return 关节反馈速度数据 - */ - std::vector get_actual_joint_speed(); - // get_target_joint_speed - /** - * @brief 获取机械臂关节当前控制力矩 - * - * @return 关节控制速度数据 - */ - std::vector get_target_joint_speed(); - /** - * @brief 获取机械臂末端在机械臂基坐标系下的实际位姿,CartesianPose = std::map,应当包括键为x,y,z,rz,ry,rx的值. - * - * @return CartesianPose - */ - CartesianPose get_actual_tcp_pose(); - /** - * @brief 获取机械臂末端在机械臂基坐标系下的控制位姿,CartesianPose = std::map,应当包括键为x,y,z,rz,ry,rx的值. - * - * @return CartesianPose - */ - CartesianPose get_target_tcp_pose(); + /** + * @brief 获取单个关节温度 + * + * @param joint_index 关节索引 + * @return double 关节当前温度 + */ + double get_joint_temp(unsigned int joint_index); - /** - * @brief 获取单个关节温度 - * - * @param joint_index 关节索引 - * @return double 关节当前温度 - */ - double get_joint_temp(unsigned int joint_index); + /** + * @brief 获取机械臂关节当前反馈力矩 + * + * @return 关节当前反馈力矩 + */ + std::vector get_actual_joint_torques(); + /** + * @brief 获取机械臂关节当前控制力矩 + * + * @return 关节当前控制力矩 + */ + std::vector get_target_joint_torques(); + /** @}*/ + /** \addtogroup IO + * @{ + */ + /** + * @brief 设置数字输出 + * @anchor DEVICENAME + * @param device 设备名字, + * ID | 设备名字 | 说明 + * ------ | ------------- | ------------- + * 0 | ROBOT | 机箱IO + * 1 | FLANGE | 法兰IO + * 2 | EXTRA | 拓展IO + * 11 | SHOULDER | 肩部按钮DI + * 12 | FLANGE_BTN | 法兰按钮DI + * + * 查看 详细信息. + * + * @param pin 端口,从 0 开始 + * @param value 待设置的值 + */ + void set_do(std::string device, unsigned int pin, unsigned int value); + /** + * @brief 获取数字输出 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin 端口,从 0 开始 + * @return 返回数字输出数值 + */ + unsigned int get_do(std::string device, unsigned int pin); + /** + * @brief 获取多个数字输出 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin 起始数字输出端口,从 0 开始 + * @param num 连续的数字输出个数 + * @return 返回多个数字输出数值 + */ + std::vector get_dos(std::string device, unsigned int pin, + unsigned int num); + /** + * @brief 获取数字输入 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin 端口,从 0 开始 + * @return 返回输入数值 + */ + unsigned int get_di(std::string device, unsigned int pin); + /** + * @brief 获取多个数字输入 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin 起始数字输入端口,从 0 开始 + * @param num 连续的数字输入个数 + * @return 返回多个数字输入 + */ + std::vector get_dis(std::string device, unsigned int pin, + unsigned int num); - /** - * @brief 获取机械臂关节当前反馈力矩 - * - * @return 关节当前反馈力矩 - */ - std::vector get_actual_joint_torques(); - /** - * @brief 获取机械臂关节当前控制力矩 - * - * @return 关节当前控制力矩 - */ - std::vector get_target_joint_torques(); + /** + * @brief 设置模拟输出 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin: 模拟输出端口,从 0 开始 + * @param value: 待设置的模拟输出值 + */ + void set_ao(std::string device, unsigned int pin, double value); + /** + * @brief 获取模拟输出 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin: 端口,从 0 开始 + * @return 返回模拟输入数值 + */ + double get_ao(std::string device, unsigned int pin); + /** + * @brief 获取多个模拟输出 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin: 起始模拟输出端口,从 0 开始 + * @param num 连续的模拟输出个数 + * @return 返回模拟输出数值 + */ + std::vector get_aos(std::string device, unsigned int pin, + unsigned int num); + /** + * @brief 获取模拟输入 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin: 端口,从 0 开始 + * @return 返回模拟输入数值 + */ + double get_ai(std::string device, unsigned int pin); + /** + * @brief 获取多个模拟输入 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin: 起始模拟输入端口,从 0 开始 + * @param num 连续的模拟输入个数 + * @return 返回多个模拟输入数值 + */ + std::vector get_ais(std::string device, unsigned int pin, + unsigned int num); + /** + * @brief 设置数字端口模式 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin 端口号,从 0 开始 + * @param value 设置的值,false为输入模式,true为输出模式 + * @return 返回是否成功 + */ + void set_dio_mode(std::string device, unsigned int pin, bool value); + /** + * @brief 获取数字端口模式 + * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. + * @param pin 端口号,从 0 开始 + * @param count 查询的连续端口数 + * @return 从pin开始的连续count个端口的当前模式 + */ + std::vector get_dios_mode(std::string device, unsigned int pin, + unsigned int count); + /** @}*/ - /** @}*/ - /** \addtogroup IO - * @{ - */ - /** - * @brief 设置数字输出 - * @anchor DEVICENAME - * @param device 设备名字, - * ID | 设备名字 | 说明 - * ------ | ------------- | ------------- - * 0 | ROBOT | 机箱IO - * 1 | FLANGE | 法兰IO - * 2 | EXTRA | 拓展IO - * 11 | SHOULDER | 肩部按钮DI - * 12 | FLANGE_BTN | 法兰按钮DI - * - * 查看 详细信息. - * - * @param pin 端口,从 0 开始 - * @param value 待设置的值 - */ - void set_do(std::string device, unsigned int pin, unsigned int value); - /** - * @brief 获取数字输出 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin 端口,从 0 开始 - * @return 返回数字输出数值 - */ - unsigned int get_do(std::string device, unsigned int pin); - /** - * @brief 获取多个数字输出 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin 起始数字输出端口,从 0 开始 - * @param num 连续的数字输出个数 - * @return 返回多个数字输出数值 - */ - std::vector get_dos(std::string device, unsigned int pin, unsigned int num); - /** - * @brief 获取数字输入 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin 端口,从 0 开始 - * @return 返回输入数值 - */ - unsigned int get_di(std::string device, unsigned int pin); - /** - * @brief 获取多个数字输入 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin 起始数字输入端口,从 0 开始 - * @param num 连续的数字输入个数 - * @return 返回多个数字输入 - */ - std::vector get_dis(std::string device, unsigned int pin, unsigned int num); + /** \addtogroup CLAW + * @{ + */ + /** + * @brief + * 设置夹爪力度(力控)和幅度(位控).如果在闭合过程中抓取到物体,则不再继续闭合以避免夹坏物体,判断的准则为这里设置的力的大小. + * + * @param force 力度(0-100) + * @param amplitude 张合幅度(0-100) + */ + void set_claw(double force, double amplitude); + /** + * @brief 获取夹爪当前数据 + * + * @return std::tuple + * 第一个数据为夹爪力度,第二个数据为幅度,第三个数据为开度是否稳定 + */ + std::tuple get_claw(); + /** + * @brief 获取夹爪当前数据 + * + * @return ClawData 数据 + */ + ClawData get_claw_data(); + /** @}*/ - /** - * @brief 设置模拟输出 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin: 模拟输出端口,从 0 开始 - * @param value: 待设置的模拟输出值 - */ - void set_ao(std::string device, unsigned int pin, double value); - /** - * @brief 获取模拟输出 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin: 端口,从 0 开始 - * @return 返回模拟输入数值 - */ - double get_ao(std::string device, unsigned int pin); - /** - * @brief 获取多个模拟输出 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin: 起始模拟输出端口,从 0 开始 - * @param num 连续的模拟输出个数 - * @return 返回模拟输出数值 - */ - std::vector get_aos(std::string device, unsigned int pin, unsigned int num); - /** - * @brief 获取模拟输入 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin: 端口,从 0 开始 - * @return 返回模拟输入数值 - */ - double get_ai(std::string device, unsigned int pin); - /** - * @brief 获取多个模拟输入 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin: 起始模拟输入端口,从 0 开始 - * @param num 连续的模拟输入个数 - * @return 返回多个模拟输入数值 - */ - std::vector get_ais(std::string device, unsigned int pin, unsigned int num); - /** - * @brief 设置数字端口模式 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin 端口号,从 0 开始 - * @param value 设置的值,false为输入模式,true为输出模式 - * @return 返回是否成功 - */ - void set_dio_mode(std::string device,unsigned int pin, bool value); - /** - * @brief 获取数字端口模式 - * @param device 设备名字,查看 @ref DEVICENAME ,可以进一步查看 详细信息. - * @param pin 端口号,从 0 开始 - * @param count 查询的连续端口数 - * @return 从pin开始的连续count个端口的当前模式 - */ - std::vector get_dios_mode(std::string device,unsigned int pin, unsigned int count); - /** @}*/ + /** \addtogroup LED + * @{ + */ + /** + * @brief 设置LED灯状态. + * + * @param mode: + * 亮灯模式.0:不变;1:关闭;2:常亮;3:呼吸;4:均分旋转;5:同色旋转;6:闪烁 + * @param speed: 速度.1:快速;2:正常;3:慢速 + * @param color: 最多包含 4 个 0 ~ 15 之间的整数 + */ + void set_led(unsigned int mode, unsigned int speed, + const std::vector &color); + /** + * @brief 设置声音 + * + * @param voice: 声音列表 + * @param volume: 音量.0:静音;1:低;2:正常;3:高 + */ + void set_voice(unsigned int voice, unsigned int volume); + /** + * @brief 开关风扇 + * + * @param status: 状态.1:关闭;2:开启 + */ + void set_fan(unsigned int status); + /** @}*/ - /** \addtogroup CLAW - * @{ - */ - /** - * @brief 设置夹爪力度(力控)和幅度(位控).如果在闭合过程中抓取到物体,则不再继续闭合以避免夹坏物体,判断的准则为这里设置的力的大小. - * - * @param force 力度(0-100) - * @param amplitude 张合幅度(0-100) - */ - void set_claw(double force, double amplitude); - /** - * @brief 获取夹爪当前数据 - * - * @return std::tuple 第一个数据为夹爪力度,第二个数据为幅度,第三个数据为开度是否稳定 - */ - std::tuple get_claw(); - /** - * @brief 获取夹爪当前数据 - * - * @return ClawData 数据 - */ - ClawData get_claw_data(); - /** @}*/ + /** \addtogroup SIGNAL + * @{ + */ - /** \addtogroup LED - * @{ - */ + /** + * @brief 设置信号量 + * + * @param index: 信号量下标(取值范围0~255) + * @param value: 待设置的信号量(32位有符号整数) + */ + void set_signal(unsigned int index, int value); + /** + * @brief 获取信号量 + * + * @param index: 信号量下标(取值范围0~255) + * @return 返回对应的信号量 + */ + int get_signal(unsigned int index); + /** + * @brief 增加指定下标的信号量值,该操作是原子的. + * + * @param index: 信号量下标(取值范围0~255) + * @param value: 待增加的信号量值 + */ + void add_signal(unsigned int index, int value); + /** @}*/ - /** - * @brief 设置LED灯状态. - * - * @param mode: 亮灯模式.0:不变;1:关闭;2:常亮;3:呼吸;4:均分旋转;5:同色旋转;6:闪烁 - * @param speed: 速度.1:快速;2:正常;3:慢速 - * @param color: 最多包含 4 个 0 ~ 15 之间的整数 - */ - void set_led(unsigned int mode,unsigned int speed,const std::vector & color); - /** - * @brief 设置声音 - * - * @param voice: 声音列表 - * @param volume: 音量.0:静音;1:低;2:正常;3:高 - */ - void set_voice(unsigned int voice,unsigned int volume); - /** - * @brief 开关风扇 - * - * @param status: 状态.1:关闭;2:开启 - */ - void set_fan(unsigned int status); - /** @}*/ - + /** \addtogroup SCENE + * @{ + */ - /** \addtogroup SIGNAL - * @{ - */ + /** + * @brief 调用场景 + * + * @param name 调用场景的名字 + * @param params 其他参数 + * @param dir 调用场景所在的文件夹名 + * @param is_parallel 是否并行 + * @param loop_to 循环次数(默认0永久循环) + * + * + */ + unsigned int start_task(const std::string &name, + const std::vector ¶ms, + const std::string &dir, bool is_parallel, + unsigned int loop_to); + /** + * @brief 调用场景 + * + * @param name: 调用场景的名字 + */ + unsigned int start_task(const std::string &name); + /** + * @brief 查询任务列表 + */ + std::vector load_task_list(); + /** + * @brief 暂停任务与运动 + * + * @param id: 任务的ID + * @param time: 暂停的时间 + * @param wait: 是否等待 + */ + void pause_task(unsigned int id, unsigned long time, bool wait); + /** + * @brief 暂停任务与运动 + * @param id: 任务的ID + */ + void pause_task(unsigned int id); + /** + * @brief 恢复任务与运动 + * + * @param id 任务的ID + */ + void resume_task(unsigned int id); + /** + * @brief 取消任务与运动. + * + * @param id 任务的ID. + */ + void cancel_task(unsigned int id); + /** + * @brief 根据已设置的Hook执行对应场景 + * + * @param id 任务的ID. + */ + unsigned int exec_hook(unsigned int id); + /** + * @brief 获取任务状态. + */ + std::string get_task_state(); + /** + * @brief 获取任务状态. + * + * @param id 任务的ID. + */ + std::string get_task_state(unsigned int id); + /** @}*/ - /** - * @brief 设置信号量 - * - * @param index: 信号量下标(取值范围0~255) - * @param value: 待设置的信号量(32位有符号整数) - */ - void set_signal(unsigned int index,int value); - /** - * @brief 获取信号量 - * - * @param index: 信号量下标(取值范围0~255) - * @return 返回对应的信号量 - */ - int get_signal(unsigned int index); - /** - * @brief 增加指定下标的信号量值,该操作是原子的. - * - * @param index: 信号量下标(取值范围0~255) - * @param value: 待增加的信号量值 - */ - void add_signal(unsigned int index,int value); - /** @}*/ + /** \addtogroup ROBOTICS + * @{ + */ + /** + * @brief 根据机械臂关节位置计算机器人末端位姿(位置的运动学正解). + * @param joint_positions: 机械臂关节位置的数组. + * @return 返回计算结果 \ref KinematicsForwardResp "KinematicsForwardResp". + * + */ + KinematicsForwardResp kinematics_forward( + const std::vector &joint_positions); - /** \addtogroup SCENE - * @{ - */ + /** + * @brief 根据机械臂的末端位姿计算关节位置(位置的运动学逆解). + * @param pose: 机械臂末端位姿,应当包括键为x,y,z,rz,ry,rx的值. + * @param joint_init_positions: 机械臂关节初始位置, 以数组形式传入. + * @return 返回计算结果 \ref KinematicsInverseResp "KinematicsInverseResp". + */ + KinematicsInverseResp kinematics_inverse( + const CartesianPose &pose, + const std::vector &joint_init_positions = {}); - /** - * @brief 调用场景 - * - * @param name 调用场景的名字 - * @param params 其他参数 - * @param dir 调用场景所在的文件夹名 - * @param is_parallel 是否并行 - * @param loop_to 循环次数(默认0永久循环) - * - * - */ - unsigned int start_task(const std::string &name,const std::vector & params,const std::string & dir, bool is_parallel,unsigned int loop_to); - /** - * @brief 调用场景 - * - * @param name: 调用场景的名字 - */ - unsigned int start_task(const std::string &name); - /** - * @brief 查询任务列表 - */ - std::vector load_task_list(); - /** - * @brief 暂停任务与运动 - * - * @param id: 任务的ID - * @param time: 暂停的时间 - * @param wait: 是否等待 - */ - void pause_task(unsigned int id,unsigned long time,bool wait); - /** - * @brief 暂停任务与运动 - * @param id: 任务的ID - */ - void pause_task(unsigned int id); - /** - * @brief 恢复任务与运动 - * - * @param id 任务的ID - */ - void resume_task(unsigned int id); - /** - * @brief 取消任务与运动. - * - * @param id 任务的ID. - */ - void cancel_task(unsigned int id); - /** - * @brief 根据已设置的Hook执行对应场景 - * - * @param id 任务的ID. - */ - unsigned int exec_hook(unsigned int id); - /** - * @brief 获取任务状态. - */ - std::string get_task_state(); - /** - * @brief 获取任务状态. - * - * @param id 任务的ID. - */ - std::string get_task_state(unsigned int id); - /** @}*/ + /** + * @brief 位姿变换乘法(等价于对应的齐次坐标矩阵乘法) + * + * @param[in] a: 位姿,应当包括键为x,y,z,rz,ry,rx的值. + * @param[in] b: 位姿,应当包括键为x,y,z,rz,ry,rx的值. + * @return CartesianPose 返回的位姿,应当包括键为x,y,z,rz,ry,rx的值. + */ + CartesianPose pose_times(const CartesianPose &a, const CartesianPose &b); - /** \addtogroup ROBOTICS - * @{ - */ - /** - * @brief 根据机械臂关节位置计算机器人末端位姿(位置的运动学正解). - * @param joint_positions: 机械臂关节位置的数组. - * @return 返回计算结果 \ref KinematicsForwardResp "KinematicsForwardResp". - * - */ - KinematicsForwardResp kinematics_forward(const std::vector & joint_positions); - - /** - * @brief 根据机械臂的末端位姿计算关节位置(位置的运动学逆解). - * @param pose: 机械臂末端位姿,应当包括键为x,y,z,rz,ry,rx的值. - * @param joint_init_positions: 机械臂关节初始位置, 以数组形式传入. - * @return 返回计算结果 \ref KinematicsInverseResp "KinematicsInverseResp". - */ - KinematicsInverseResp kinematics_inverse(const CartesianPose & pose, const std::vector & joint_init_positions = {}); - - /** - * @brief 位姿变换乘法(等价于对应的齐次坐标矩阵乘法) - * - * @param[in] a: 位姿,应当包括键为x,y,z,rz,ry,rx的值. - * @param[in] b: 位姿,应当包括键为x,y,z,rz,ry,rx的值. - * @return CartesianPose 返回的位姿,应当包括键为x,y,z,rz,ry,rx的值. - */ - CartesianPose pose_times(const CartesianPose & a, const CartesianPose & b); + /** + * @brief 位姿变换的逆(等价于对应的齐次坐标矩的逆) + * + * @param in: 位姿,应当包括键为x,y,z,rz,ry,rx的值. + * @return CartesianPose 返回位姿变换的逆,应当包括键为x,y,z,rz,ry,rx的值. + */ + CartesianPose pose_inverse(const CartesianPose &in); + /** @}*/ - /** - * @brief 位姿变换的逆(等价于对应的齐次坐标矩的逆) - * - * @param in: 位姿,应当包括键为x,y,z,rz,ry,rx的值. - * @return CartesianPose 返回位姿变换的逆,应当包括键为x,y,z,rz,ry,rx的值. - */ - CartesianPose pose_inverse(const CartesianPose & in); - /** @}*/ + /** \addtogroup FILE + * @{ + */ + /** + * @brief 保存文件(以字节形式). + * + * @param dir: 保存的文件路径. + * @param name: 保存的文件名. + * @param is_dir: 要保存的文件是否为文件夹. + * @param data: 文件字节. + */ + void save_file(const std::string &dir, const std::string &name, bool is_dir, + const std::string &data); + /** + * @brief 重命名文件 + * + * @param from_dir: 源文件所在的文件夹. + * @param from_name: 源文件名称. + * @param to_dir: 目标文件文件夹. + * @param to_name: 目标文件文件名. + */ + void rename_file(const std::string &from_dir, const std::string &from_name, + const std::string &to_dir, const std::string &to_name); - /** \addtogroup FILE - * @{ - */ - /** - * @brief 保存文件(以字节形式). - * - * @param dir: 保存的文件路径. - * @param name: 保存的文件名. - * @param is_dir: 要保存的文件是否为文件夹. - * @param data: 文件字节. - */ - void save_file(const std::string &dir,const std::string &name,bool is_dir,const std::string &data); - /** - * @brief 重命名文件 - * - * @param from_dir: 源文件所在的文件夹. - * @param from_name: 源文件名称. - * @param to_dir: 目标文件文件夹. - * @param to_name: 目标文件文件名. - */ - void rename_file(const std::string &from_dir,const std::string &from_name,const std::string &to_dir,const std::string &to_name); - - /** - * @brief 查询文件 - * - * @param dir: 文件的目录 - * @param name: 文件名 - * - * @return 文件的具体内容 - */ - std::tuple load_file(const std::string &dir,const std::string &name); - - /** - * @brief 查询文件列表. - * - * @param dir: 文件的目录. - * @param prefix: 前缀. - * @param suffix: 后缀. - * - * @return 文件列表. - */ - std::vector> load_file_list(const std::string &dir,const std::string &prefix,const std::string &suffix); - /** - * @brief 将文件从文件系统中压缩到zip文件. - * - * @param from_dir 源文件的目录. - * @param files 源文件的文件名. - * @param to_dir 压缩后文件的路径. - * @param name 压缩后文件的名称. - */ - // void zip(const std::string &from_dir, std::vector files, const std::string &to_dir, const std::string &name); - // /** - // * @brief 将zip文件解压到文件系统. - // * - // * @param from_dir zip文件的路径. - // * @param name zip文件的名称. - // * @param files zip文件内的文件名. - // * @param to_dir 解压到的路径. - // */ - // void unzip(const std::string &from_dir, const std::string &name, std::vector files, const std::string &to_dir); - // /** - // * @brief 查询文件列表. - // * - // * @brief 目标zip文件名. - // * @param dir 文件的目录. - // * @param prefix 前缀. - // * @param suffix 后缀. - // * - // * @return 文件列表. - // */ - // //std::vector> load_zip_list(const std::string &zip,const std::string &dir,const std::string &prefix,const std::string &suffix); + /** + * @brief 查询文件 + * + * @param dir: 文件的目录 + * @param name: 文件名 + * + * @return 文件的具体内容 + */ + std::tuple load_file(const std::string &dir, + const std::string &name); - /** @}*/ + /** + * @brief 查询文件列表. + * + * @param dir: 文件的目录. + * @param prefix: 前缀. + * @param suffix: 后缀. + * + * @return 文件列表. + */ + std::vector> load_file_list( + const std::string &dir, const std::string &prefix, + const std::string &suffix); + /** + * @brief 将文件从文件系统中压缩到zip文件. + * + * @param from_dir 源文件的目录. + * @param files 源文件的文件名. + * @param to_dir 压缩后文件的路径. + * @param name 压缩后文件的名称. + */ + // void zip(const std::string &from_dir, std::vector files, const + // std::string &to_dir, const std::string &name); + // /** + // * @brief 将zip文件解压到文件系统. + // * + // * @param from_dir zip文件的路径. + // * @param name zip文件的名称. + // * @param files zip文件内的文件名. + // * @param to_dir 解压到的路径. + // */ + // void unzip(const std::string &from_dir, const std::string &name, + // std::vector files, const std::string &to_dir); + // /** + // * @brief 查询文件列表. + // * + // * @brief 目标zip文件名. + // * @param dir 文件的目录. + // * @param prefix 前缀. + // * @param suffix 后缀. + // * + // * @return 文件列表. + // */ + // //std::vector> load_zip_list(const std::string + // &zip,const std::string &dir,const std::string &prefix,const std::string + // &suffix); - /** \addtogroup CONFIG - * @{ - */ - /** - * @brief 设置工具中心点(TCP)坐标,坐标值相对于工具坐标系. - * - * @param tcp 参数为六元组,表示一个空间位置变换. - */ - void set_tcp(std::array tcp); - /** - * @brief 获取当前机器人工具中心点设置. - * - * @return 当前机器人的工具中心点参数,为六元组. - */ - std::array get_tcp(); - /** - * @brief 设置速度因子. - * - * @param factor 速度因子百分比,范围0-100. - */ - void set_velocity_factor(int factor); - /** - * @brief 获取当前的速度因子. - * - * @return 速度因子百分比. - */ - int get_velocity_factor(); - /** - * @brief 设置机器人末端负载. - * - * @param mass 末端负载的质量(kg). - * @param cog 质心相对于TCP坐标系的偏移. - */ - void set_payload(double mass, std::map cog); - /** - * @brief 设置机器人末端负载质量. - * - * @param mass 末端负载的质量(kg). - */ - void set_payload_mass(double mass); - /** - * @brief 设置机器人末端负载重心. - * - * @param cog 质心相对于TCP坐标系的偏移. - */ - void set_payload_cog(std::map cog); - /** - * @brief 获取末端负载设置. - * - * @return 由负载质量mass和负载偏移组成的元组. - */ - std::map get_payload(); - /** - * @brief 设置机器人重力加速度方向. - * - * @param gravity 相对于机器人基座标的重力方向. - */ - void set_gravity(std::map gravity); - /** - * @brief 获取机器人重力加速度的方向. - * - * @return 相对于机器人基座标的重力方向. - */ - std::map get_gravity(); - /** - * @brief 从资源库加载tcp. - * - * @param name 点位名称. - * @param dir 点位目录. - */ - CartesianPose load_tcp(std::string name, std::string dir = ""); - /** @}*/ + /** @}*/ + /** \addtogroup CONFIG + * @{ + */ + /** + * @brief 设置工具中心点(TCP)坐标,坐标值相对于工具坐标系. + * + * @param tcp 参数为六元组,表示一个空间位置变换. + */ + void set_tcp(std::array tcp); + /** + * @brief 获取当前机器人工具中心点设置. + * + * @return 当前机器人的工具中心点参数,为六元组. + */ + std::array get_tcp(); + /** + * @brief 设置速度因子. + * + * @param factor 速度因子百分比,范围0-100. + */ + void set_velocity_factor(int factor); + /** + * @brief 获取当前的速度因子. + * + * @return 速度因子百分比. + */ + int get_velocity_factor(); + /** + * @brief 设置机器人末端负载. + * + * @param mass 末端负载的质量(kg). + * @param cog 质心相对于TCP坐标系的偏移. + */ + void set_payload(double mass, std::map cog); + /** + * @brief 设置机器人末端负载质量. + * + * @param mass 末端负载的质量(kg). + */ + void set_payload_mass(double mass); + /** + * @brief 设置机器人末端负载重心. + * + * @param cog 质心相对于TCP坐标系的偏移. + */ + void set_payload_cog(std::map cog); + /** + * @brief 获取末端负载设置. + * + * @return 由负载质量mass和负载偏移组成的元组. + */ + std::map get_payload(); + /** + * @brief 设置机器人重力加速度方向. + * + * @param gravity 相对于机器人基座标的重力方向. + */ + void set_gravity(std::map gravity); + /** + * @brief 获取机器人重力加速度的方向. + * + * @return 相对于机器人基座标的重力方向. + */ + std::map get_gravity(); + /** + * @brief 从资源库加载tcp. + * + * @param name 点位名称. + * @param dir 点位目录. + */ + CartesianPose load_tcp(std::string name, std::string dir = ""); + /** @}*/ - /** \addtogroup MODBUS - * @{ - */ + /** \addtogroup MODBUS + * @{ + */ - /** - * @brief 写单个线圈. - * - * @param device 设备名称. - * @param addr 寄存器地址. - * @param value 待设置的值. - */ - void write_single_coil(std::string device, std::string addr, bool value); + /** + * @brief 写单个线圈. + * + * @param device 设备名称. + * @param addr 寄存器地址. + * @param value 待设置的值. + */ + void write_single_coil(std::string device, std::string addr, bool value); - /** - * @brief 写多个线圈 - * - * @param device 设备名称. - * @param addr 寄存器地址. - * @param values 待设置的值. - */ - void wirte_multiple_coils(std::string device, std::string addr, std::vector values); + /** + * @brief 写多个线圈 + * + * @param device 设备名称. + * @param addr 寄存器地址. + * @param values 待设置的值. + */ + void wirte_multiple_coils(std::string device, std::string addr, + std::vector values); - /** - * @brief 读线圈 - * - * @param device 设备名称. - * @param addr 寄存器地址. - * @param num 连续数量. - */ - std::vector read_coils(std::string device, std::string addr, unsigned int num); - /** - * @brief 读离散输入 - * - * @param device 设备名称. - * @param addr 寄存器地址. - * @param num 连续数量. - */ - std::vector read_discrete_inputs(std::string device, std::string addr, unsigned int num); + /** + * @brief 读线圈 + * + * @param device 设备名称. + * @param addr 寄存器地址. + * @param num 连续数量. + */ + std::vector read_coils(std::string device, std::string addr, + unsigned int num); + /** + * @brief 读离散输入 + * + * @param device 设备名称. + * @param addr 寄存器地址. + * @param num 连续数量. + */ + std::vector read_discrete_inputs(std::string device, std::string addr, + unsigned int num); - /** - * @brief 写单个寄存器 - * - * @param device 设备名称. - * @param addr 寄存器地址. - * @param value 待设置的值. - */ - void write_single_register(std::string device, std::string addr, unsigned int value); - /** - * @brief 写多个寄存器 - * - * @param device 设备名称. - * @param addr 寄存器地址. - * @param values 待设置的值. - */ - void write_multiple_registers(std::string device, std::string addr, std::vector values); + /** + * @brief 写单个寄存器 + * + * @param device 设备名称. + * @param addr 寄存器地址. + * @param value 待设置的值. + */ + void write_single_register(std::string device, std::string addr, + unsigned int value); + /** + * @brief 写多个寄存器 + * + * @param device 设备名称. + * @param addr 寄存器地址. + * @param values 待设置的值. + */ + void write_multiple_registers(std::string device, std::string addr, + std::vector values); - /** - * @brief 读保持寄存器 - * - * @param device 设备名称 - * @param addr 寄存器地址 - * @param num 连续数量 - */ - std::vector read_holding_registers(std::string device, std::string addr, unsigned int num); - /** - * @brief 读输入寄存器 - * - * @param device 设备名称 - * @param addr 寄存器地址 - * @param num 连续数量 - */ - std::vector read_input_registers(std::string device, std::string addr, unsigned int num); - /** @}*/ + /** + * @brief 读保持寄存器 + * + * @param device 设备名称 + * @param addr 寄存器地址 + * @param num 连续数量 + */ + std::vector read_holding_registers(std::string device, + std::string addr, + unsigned int num); + /** + * @brief 读输入寄存器 + * + * @param device 设备名称 + * @param addr 寄存器地址 + * @param num 连续数量 + */ + std::vector read_input_registers(std::string device, + std::string addr, + unsigned int num); + /** @}*/ -/** \addtogroup SERIAL - * @{ - */ + /** \addtogroup SERIAL + * @{ + */ - /** - * @brief 设置串口波特率. - * - * @param device 设备名称. - * @param baud_rate 波特率. - */ - void set_serial_baud_rate(std::string device, unsigned int baud_rate); - /** - * @brief 设置串口校验位. - * - * @param device 设备名称. - * @param parity 校验位. 0:无校验; 1:奇校验; 2:偶校验. - * - */ - void set_serial_parity(std::string device, unsigned int parity); - /** @}*/ - protected: - std::unique_ptr impl_; /*!< 内部实现数据结构,用户无需关注. */ - }; + /** + * @brief 设置串口波特率. + * + * @param device 设备名称. + * @param baud_rate 波特率. + */ + void set_serial_baud_rate(std::string device, unsigned int baud_rate); + /** + * @brief 设置串口校验位. + * + * @param device 设备名称. + * @param parity 校验位. 0:无校验; 1:奇校验; 2:偶校验. + * + */ + void set_serial_parity(std::string device, unsigned int parity); + /** @}*/ + protected: + std::unique_ptr impl_; /*!< 内部实现数据结构,用户无需关注. */ +}; - } +} // namespace l_master -} // namespace l_master_sdk +} // namespace lebai diff --git a/sdk/src/discovery.cc b/sdk/src/discovery.cc index 6a30bae..85b282f 100644 --- a/sdk/src/discovery.cc +++ b/sdk/src/discovery.cc @@ -14,41 +14,30 @@ * limitations under the License. */ -#include #include +#include #include "discovery_impl.hh" -namespace lebai -{ +namespace lebai { - namespace zeroconf - { +namespace zeroconf { - std::string ControllerInfo::str() - { - std::string str; - str += "{'hostname':" + hostname + ","; - str += "'ip_address':" + ip_address + ","; - str += "'mac_address':" + mac_address + ","; - str += "'model':" + model + ","; - str += "'ds_version':" + ds_version + ","; - str += "'rc_version':" + rc_version + ","; - str += "'id':" + id+"}"; - return str; - } - Discovery::Discovery() - { - impl_ = std::make_unique(); - } - Discovery::~Discovery() - { - } +std::string ControllerInfo::str() { + std::string str; + str += "{'hostname':" + hostname + ","; + str += "'ip_address':" + ip_address + ","; + str += "'mac_address':" + mac_address + ","; + str += "'model':" + model + ","; + str += "'ds_version':" + ds_version + ","; + str += "'rc_version':" + rc_version + ","; + str += "'id':" + id + "}"; + return str; +} +Discovery::Discovery() { impl_ = std::make_unique(); } +Discovery::~Discovery() {} - std::vector Discovery::resolve() - { - return impl_->resolve(); - } +std::vector Discovery::resolve() { return impl_->resolve(); } - } +} // namespace zeroconf -} // namespace zeroconf \ No newline at end of file +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/discovery_impl.cc b/sdk/src/discovery_impl.cc index 441061f..a9bde8b 100644 --- a/sdk/src/discovery_impl.cc +++ b/sdk/src/discovery_impl.cc @@ -14,9 +14,6 @@ * limitations under the License. */ -#include "discovery_impl.hh" -#include -#include #ifdef _WIN32 #include #include @@ -26,542 +23,502 @@ #include #include #endif -#include - +#include +#include "discovery_impl.hh" -namespace lebai -{ - namespace zeroconf - { - static char addrbuffer[64]; - static char entrybuffer[256]; - static char namebuffer[256]; - static char sendbuffer[1024]; - static mdns_record_txt_t txtbuffer[128]; - static struct sockaddr_in service_address_ipv4; - static struct sockaddr_in6 service_address_ipv6; - static std::vector g_controller_info_array; - ControllerInfo g_controller_info; +namespace lebai { +namespace zeroconf { +static char addrbuffer[64]; +static char entrybuffer[256]; +static char namebuffer[256]; +static char sendbuffer[1024]; +static mdns_record_txt_t txtbuffer[128]; +static struct sockaddr_in service_address_ipv4; +static struct sockaddr_in6 service_address_ipv6; +static std::vector g_controller_info_array; +ControllerInfo g_controller_info; - static int has_ipv4; - static int has_ipv6; - static mdns_string_t - ipv4_address_to_string(char* buffer, size_t capacity, const struct sockaddr_in* addr, - size_t addrlen) { - char host[NI_MAXHOST] = {0}; - char service[NI_MAXSERV] = {0}; - int ret = getnameinfo((const struct sockaddr*)addr, (socklen_t)addrlen, host, NI_MAXHOST, - service, NI_MAXSERV, NI_NUMERICSERV | NI_NUMERICHOST); - int len = 0; - if (ret == 0) { - if (addr->sin_port != 0) - len = snprintf(buffer, capacity, "%s:%s", host, service); - else - len = snprintf(buffer, capacity, "%s", host); - } - if (len >= (int)capacity) - len = (int)capacity - 1; - mdns_string_t str; - str.str = buffer; - str.length = len; - return str; - } - static mdns_string_t - ipv6_address_to_string(char* buffer, size_t capacity, const struct sockaddr_in6* addr, - size_t addrlen) { - char host[NI_MAXHOST] = {0}; - char service[NI_MAXSERV] = {0}; - int ret = getnameinfo((const struct sockaddr*)addr, (socklen_t)addrlen, host, NI_MAXHOST, - service, NI_MAXSERV, NI_NUMERICSERV | NI_NUMERICHOST); - int len = 0; - if (ret == 0) { - if (addr->sin6_port != 0) - len = snprintf(buffer, capacity, "[%s]:%s", host, service); - else - len = snprintf(buffer, capacity, "%s", host); - } - if (len >= (int)capacity) - len = (int)capacity - 1; - mdns_string_t str; - str.str = buffer; - str.length = len; - return str; - } +static int has_ipv4; +static int has_ipv6; +static mdns_string_t ipv4_address_to_string(char* buffer, size_t capacity, + const struct sockaddr_in* addr, + size_t addrlen) { + char host[NI_MAXHOST] = {0}; + char service[NI_MAXSERV] = {0}; + int ret = getnameinfo((const struct sockaddr*)addr, (socklen_t)addrlen, host, + NI_MAXHOST, service, NI_MAXSERV, + NI_NUMERICSERV | NI_NUMERICHOST); + int len = 0; + if (ret == 0) { + if (addr->sin_port != 0) + len = snprintf(buffer, capacity, "%s:%s", host, service); + else + len = snprintf(buffer, capacity, "%s", host); + } + if (len >= (int)capacity) len = (int)capacity - 1; + mdns_string_t str; + str.str = buffer; + str.length = len; + return str; +} +static mdns_string_t ipv6_address_to_string(char* buffer, size_t capacity, + const struct sockaddr_in6* addr, + size_t addrlen) { + char host[NI_MAXHOST] = {0}; + char service[NI_MAXSERV] = {0}; + int ret = getnameinfo((const struct sockaddr*)addr, (socklen_t)addrlen, host, + NI_MAXHOST, service, NI_MAXSERV, + NI_NUMERICSERV | NI_NUMERICHOST); + int len = 0; + if (ret == 0) { + if (addr->sin6_port != 0) + len = snprintf(buffer, capacity, "[%s]:%s", host, service); + else + len = snprintf(buffer, capacity, "%s", host); + } + if (len >= (int)capacity) len = (int)capacity - 1; + mdns_string_t str; + str.str = buffer; + str.length = len; + return str; +} - static mdns_string_t - ip_address_to_string(char* buffer, size_t capacity, const struct sockaddr* addr, size_t addrlen) { - if (addr->sa_family == AF_INET6) - return ipv6_address_to_string(buffer, capacity, (const struct sockaddr_in6*)addr, addrlen); - return ipv4_address_to_string(buffer, capacity, (const struct sockaddr_in*)addr, addrlen); - } - static int query_callback(int sock, const struct sockaddr* from, size_t addrlen, mdns_entry_type_t entry, - uint16_t query_id, uint16_t rtype, uint16_t rclass, uint32_t ttl, const void* data, - size_t size, size_t name_offset, size_t name_length, size_t record_offset, - size_t record_length, void* user_data) { - (void)sizeof(sock); - (void)sizeof(query_id); - (void)sizeof(name_length); - (void)sizeof(user_data); - mdns_string_t fromaddrstr = ip_address_to_string(addrbuffer, sizeof(addrbuffer), from, addrlen); - const char* entrytype = (entry == MDNS_ENTRYTYPE_ANSWER) ? - "answer" : - ((entry == MDNS_ENTRYTYPE_AUTHORITY) ? "authority" : "additional"); - mdns_string_t entrystr = - mdns_string_extract(data, size, &name_offset, entrybuffer, sizeof(entrybuffer)); - if (rtype == MDNS_RECORDTYPE_PTR) { - mdns_string_t namestr = mdns_record_parse_ptr(data, size, record_offset, record_length, - namebuffer, sizeof(namebuffer)); - // printf("%.*s : %s %.*s PTR %.*s rclass 0x%x ttl %u length %d\n", - // MDNS_STRING_FORMAT(fromaddrstr), entrytype, MDNS_STRING_FORMAT(entrystr), - // MDNS_STRING_FORMAT(namestr), rclass, ttl, (int)record_length); - g_controller_info.hostname = std::string(namestr.str, namestr.length); - g_controller_info.hostname = g_controller_info.hostname.substr(0, g_controller_info.hostname.find(".")); - } else if (rtype == MDNS_RECORDTYPE_SRV) { - mdns_record_srv_t srv = mdns_record_parse_srv(data, size, record_offset, record_length, - namebuffer, sizeof(namebuffer)); - // printf("%.*s : %s %.*s SRV %.*s priority %d weight %d port %d\n", - // MDNS_STRING_FORMAT(fromaddrstr), entrytype, MDNS_STRING_FORMAT(entrystr), - // MDNS_STRING_FORMAT(srv.name), srv.priority, srv.weight, srv.port); - } else if (rtype == MDNS_RECORDTYPE_A) { - struct sockaddr_in addr; - mdns_record_parse_a(data, size, record_offset, record_length, &addr); - mdns_string_t addrstr = - ipv4_address_to_string(namebuffer, sizeof(namebuffer), &addr, sizeof(addr)); - // printf("%.*s : %s %.*s A %.*s\n", MDNS_STRING_FORMAT(fromaddrstr), entrytype, - // MDNS_STRING_FORMAT(entrystr), MDNS_STRING_FORMAT(addrstr)); - g_controller_info.ip_address = std::string(addrstr.str, addrstr.length); - } else if (rtype == MDNS_RECORDTYPE_AAAA) { - struct sockaddr_in6 addr; - mdns_record_parse_aaaa(data, size, record_offset, record_length, &addr); - mdns_string_t addrstr = - ipv6_address_to_string(namebuffer, sizeof(namebuffer), &addr, sizeof(addr)); - // printf("%.*s : %s %.*s AAAA %.*s\n", MDNS_STRING_FORMAT(fromaddrstr), entrytype, - // MDNS_STRING_FORMAT(entrystr), MDNS_STRING_FORMAT(addrstr)); - } else if (rtype == MDNS_RECORDTYPE_TXT) { - size_t parsed = mdns_record_parse_txt(data, size, record_offset, record_length, txtbuffer, - sizeof(txtbuffer) / sizeof(mdns_record_txt_t)); - for (size_t itxt = 0; itxt < parsed; ++itxt) { - if (txtbuffer[itxt].value.length) { - // printf("%.*s : %s %.*s TXT %.*s = %.*s\n", MDNS_STRING_FORMAT(fromaddrstr), - // entrytype, MDNS_STRING_FORMAT(entrystr), - // MDNS_STRING_FORMAT(txtbuffer[itxt].key), - // MDNS_STRING_FORMAT(txtbuffer[itxt].value)); - // controller_info.hostname = controller_info.hostname.substr(0, controller_info.hostname.find(".")); - std::string key = std::string(txtbuffer[itxt].key.str, txtbuffer[itxt].key.length); - if(key == "model") - { - g_controller_info.model = std::string(txtbuffer[itxt].value.str,txtbuffer[itxt].value.length); - } - else if(key == "ds") - { - g_controller_info.ds_version = std::string(txtbuffer[itxt].value.str,txtbuffer[itxt].value.length); - } - else if(key == "rc") - { - g_controller_info.rc_version = std::string(txtbuffer[itxt].value.str,txtbuffer[itxt].value.length); - } - else if(key == "id") - { - g_controller_info.id = std::string(txtbuffer[itxt].value.str,txtbuffer[itxt].value.length); - } - else if(key == "mac") - { - g_controller_info.mac_address = std::string(txtbuffer[itxt].value.str,txtbuffer[itxt].value.length); - } - } else { - // printf("%.*s : %s %.*s TXT %.*s\n", MDNS_STRING_FORMAT(fromaddrstr), entrytype, - // MDNS_STRING_FORMAT(entrystr), MDNS_STRING_FORMAT(txtbuffer[itxt].key)); - } +static mdns_string_t ip_address_to_string(char* buffer, size_t capacity, + const struct sockaddr* addr, + size_t addrlen) { + if (addr->sa_family == AF_INET6) + return ipv6_address_to_string(buffer, capacity, + (const struct sockaddr_in6*)addr, addrlen); + return ipv4_address_to_string(buffer, capacity, + (const struct sockaddr_in*)addr, addrlen); +} +static int query_callback(int sock, const struct sockaddr* from, size_t addrlen, + mdns_entry_type_t entry, uint16_t query_id, + uint16_t rtype, uint16_t rclass, uint32_t ttl, + const void* data, size_t size, size_t name_offset, + size_t name_length, size_t record_offset, + size_t record_length, void* user_data) { + (void)sizeof(sock); + (void)sizeof(query_id); + (void)sizeof(name_length); + (void)sizeof(user_data); + mdns_string_t fromaddrstr = + ip_address_to_string(addrbuffer, sizeof(addrbuffer), from, addrlen); + const char* entrytype = + (entry == MDNS_ENTRYTYPE_ANSWER) + ? "answer" + : ((entry == MDNS_ENTRYTYPE_AUTHORITY) ? "authority" : "additional"); + mdns_string_t entrystr = mdns_string_extract( + data, size, &name_offset, entrybuffer, sizeof(entrybuffer)); + if (rtype == MDNS_RECORDTYPE_PTR) { + mdns_string_t namestr = + mdns_record_parse_ptr(data, size, record_offset, record_length, + namebuffer, sizeof(namebuffer)); + // printf("%.*s : %s %.*s PTR %.*s rclass 0x%x ttl %u length %d\n", + // MDNS_STRING_FORMAT(fromaddrstr), entrytype, + // MDNS_STRING_FORMAT(entrystr), MDNS_STRING_FORMAT(namestr), rclass, + // ttl, (int)record_length); + g_controller_info.hostname = std::string(namestr.str, namestr.length); + g_controller_info.hostname = g_controller_info.hostname.substr( + 0, g_controller_info.hostname.find(".")); + } else if (rtype == MDNS_RECORDTYPE_SRV) { + mdns_record_srv_t srv = + mdns_record_parse_srv(data, size, record_offset, record_length, + namebuffer, sizeof(namebuffer)); + // printf("%.*s : %s %.*s SRV %.*s priority %d weight %d port %d\n", + // MDNS_STRING_FORMAT(fromaddrstr), entrytype, + // MDNS_STRING_FORMAT(entrystr), MDNS_STRING_FORMAT(srv.name), + // srv.priority, srv.weight, srv.port); + } else if (rtype == MDNS_RECORDTYPE_A) { + struct sockaddr_in addr; + mdns_record_parse_a(data, size, record_offset, record_length, &addr); + mdns_string_t addrstr = ipv4_address_to_string( + namebuffer, sizeof(namebuffer), &addr, sizeof(addr)); + // printf("%.*s : %s %.*s A %.*s\n", MDNS_STRING_FORMAT(fromaddrstr), + // entrytype, + // MDNS_STRING_FORMAT(entrystr), MDNS_STRING_FORMAT(addrstr)); + g_controller_info.ip_address = std::string(addrstr.str, addrstr.length); + } else if (rtype == MDNS_RECORDTYPE_AAAA) { + struct sockaddr_in6 addr; + mdns_record_parse_aaaa(data, size, record_offset, record_length, &addr); + mdns_string_t addrstr = ipv6_address_to_string( + namebuffer, sizeof(namebuffer), &addr, sizeof(addr)); + // printf("%.*s : %s %.*s AAAA %.*s\n", MDNS_STRING_FORMAT(fromaddrstr), + // entrytype, + // MDNS_STRING_FORMAT(entrystr), MDNS_STRING_FORMAT(addrstr)); + } else if (rtype == MDNS_RECORDTYPE_TXT) { + size_t parsed = mdns_record_parse_txt( + data, size, record_offset, record_length, txtbuffer, + sizeof(txtbuffer) / sizeof(mdns_record_txt_t)); + for (size_t itxt = 0; itxt < parsed; ++itxt) { + if (txtbuffer[itxt].value.length) { + // printf("%.*s : %s %.*s TXT %.*s = %.*s\n", + // MDNS_STRING_FORMAT(fromaddrstr), + // entrytype, MDNS_STRING_FORMAT(entrystr), + // MDNS_STRING_FORMAT(txtbuffer[itxt].key), + // MDNS_STRING_FORMAT(txtbuffer[itxt].value)); + // controller_info.hostname = controller_info.hostname.substr(0, + // controller_info.hostname.find(".")); + std::string key = + std::string(txtbuffer[itxt].key.str, txtbuffer[itxt].key.length); + if (key == "model") { + g_controller_info.model = std::string(txtbuffer[itxt].value.str, + txtbuffer[itxt].value.length); + } else if (key == "ds") { + g_controller_info.ds_version = std::string( + txtbuffer[itxt].value.str, txtbuffer[itxt].value.length); + } else if (key == "rc") { + g_controller_info.rc_version = std::string( + txtbuffer[itxt].value.str, txtbuffer[itxt].value.length); + } else if (key == "id") { + g_controller_info.id = std::string(txtbuffer[itxt].value.str, + txtbuffer[itxt].value.length); + } else if (key == "mac") { + g_controller_info.mac_address = std::string( + txtbuffer[itxt].value.str, txtbuffer[itxt].value.length); } } else { - // printf("%.*s : %s %.*s type %u rclass 0x%x ttl %u length %d\n", - // MDNS_STRING_FORMAT(fromaddrstr), entrytype, MDNS_STRING_FORMAT(entrystr), rtype, - // rclass, ttl, (int)record_length); + // printf("%.*s : %s %.*s TXT %.*s\n", MDNS_STRING_FORMAT(fromaddrstr), + // entrytype, + // MDNS_STRING_FORMAT(entrystr), + // MDNS_STRING_FORMAT(txtbuffer[itxt].key)); } - if(!g_controller_info.hostname.empty() && - !g_controller_info.model.empty() && - !g_controller_info.ds_version.empty() && - !g_controller_info.rc_version.empty() && - !g_controller_info.id.empty() && - !g_controller_info.mac_address.empty() && - !g_controller_info.ip_address.empty()) - { - g_controller_info_array.push_back(g_controller_info); - g_controller_info.hostname.clear(); - g_controller_info.model.clear(); - g_controller_info.ds_version.clear(); - g_controller_info.rc_version.clear(); - g_controller_info.id.clear(); - g_controller_info.mac_address.clear(); - g_controller_info.ip_address.clear(); - } - return 0; - } - Discovery::DiscoveryImpl::DiscoveryImpl() - { - } - Discovery::DiscoveryImpl::~DiscoveryImpl() {} - std::vector Discovery::DiscoveryImpl::resolve() - { - mdns_query_t query[16]; - size_t query_count = 0; - query[query_count].name = PTR_.c_str(); - query[query_count].type = MDNS_RECORDTYPE_PTR; - query[query_count].length = strlen(query[query_count].name); - query_count++; - send_mdns_query(query, query_count); - // for(auto && controller_info : g_controller_info_array) - // { - // std::cout<<"================================\n"; - // std::cout<<"controller_info.hostname "< Discovery::DiscoveryImpl::resolve() { + mdns_query_t query[16]; + size_t query_count = 0; + query[query_count].name = PTR_.c_str(); + query[query_count].type = MDNS_RECORDTYPE_PTR; + query[query_count].length = strlen(query[query_count].name); + query_count++; + send_mdns_query(query, query_count); + // for(auto && controller_info : g_controller_info_array) + // { + // std::cout<<"================================\n"; + // std::cout<<"controller_info.hostname "<= nfds) - nfds = sockets[isock] + 1; - FD_SET(sockets[isock], &readfs); - } + int nfds = 0; + fd_set readfs; + FD_ZERO(&readfs); + for (int isock = 0; isock < num_sockets; ++isock) { + if (sockets[isock] >= nfds) nfds = sockets[isock] + 1; + FD_SET(sockets[isock], &readfs); + } - res = select(nfds, &readfs, 0, 0, &timeout); - if (res > 0) - { - g_controller_info.hostname.clear(); - g_controller_info.model.clear(); - g_controller_info.ds_version.clear(); - g_controller_info.rc_version.clear(); - g_controller_info.id.clear(); - g_controller_info.mac_address.clear(); - g_controller_info.ip_address.clear(); - for (int isock = 0; isock < num_sockets; ++isock) - { - if (FD_ISSET(sockets[isock], &readfs)) - { - int rec = mdns_query_recv(sockets[isock], buffer, capacity, query_callback, - user_data, query_id[isock]); - if (rec > 0) - records += rec; - } - FD_SET(sockets[isock], &readfs); - } + res = select(nfds, &readfs, 0, 0, &timeout); + if (res > 0) { + g_controller_info.hostname.clear(); + g_controller_info.model.clear(); + g_controller_info.ds_version.clear(); + g_controller_info.rc_version.clear(); + g_controller_info.id.clear(); + g_controller_info.mac_address.clear(); + g_controller_info.ip_address.clear(); + for (int isock = 0; isock < num_sockets; ++isock) { + if (FD_ISSET(sockets[isock], &readfs)) { + int rec = mdns_query_recv(sockets[isock], buffer, capacity, + query_callback, user_data, query_id[isock]); + if (rec > 0) records += rec; } - } while (res > 0); + FD_SET(sockets[isock], &readfs); + } + } + } while (res > 0); - // printf("Read %d records\n", records); + // printf("Read %d records\n", records); - free(buffer); + free(buffer); - for (int isock = 0; isock < num_sockets; ++isock) - mdns_socket_close(sockets[isock]); - // printf("Closed socket%s\n", num_sockets ? "s" : ""); - return; - } + for (int isock = 0; isock < num_sockets; ++isock) + mdns_socket_close(sockets[isock]); + // printf("Closed socket%s\n", num_sockets ? "s" : ""); + return; +} - int - Discovery::DiscoveryImpl::open_client_sockets(int *sockets, int max_sockets, int port) - { - // When sending, each socket can only send to one network interface - // Thus we need to open one socket for each interface and address family - int num_sockets = 0; +int Discovery::DiscoveryImpl::open_client_sockets(int* sockets, int max_sockets, + int port) { + // When sending, each socket can only send to one network interface + // Thus we need to open one socket for each interface and address family + int num_sockets = 0; #ifdef _WIN32 - IP_ADAPTER_ADDRESSES *adapter_address = 0; - ULONG address_size = 8000; - unsigned int ret; - unsigned int num_retries = 4; - do - { - adapter_address = (IP_ADAPTER_ADDRESSES *)malloc(address_size); - ret = GetAdaptersAddresses(AF_UNSPEC, GAA_FLAG_SKIP_MULTICAST | GAA_FLAG_SKIP_ANYCAST, 0, - adapter_address, &address_size); - if (ret == ERROR_BUFFER_OVERFLOW) - { - free(adapter_address); - adapter_address = 0; - address_size *= 2; - } - else - { - break; - } - } while (num_retries-- > 0); + IP_ADAPTER_ADDRESSES* adapter_address = 0; + ULONG address_size = 8000; + unsigned int ret; + unsigned int num_retries = 4; + do { + adapter_address = (IP_ADAPTER_ADDRESSES*)malloc(address_size); + ret = GetAdaptersAddresses(AF_UNSPEC, + GAA_FLAG_SKIP_MULTICAST | GAA_FLAG_SKIP_ANYCAST, + 0, adapter_address, &address_size); + if (ret == ERROR_BUFFER_OVERFLOW) { + free(adapter_address); + adapter_address = 0; + address_size *= 2; + } else { + break; + } + } while (num_retries-- > 0); - if (!adapter_address || (ret != NO_ERROR)) - { - free(adapter_address); - printf("Failed to get network adapter addresses\n"); - return num_sockets; - } + if (!adapter_address || (ret != NO_ERROR)) { + free(adapter_address); + printf("Failed to get network adapter addresses\n"); + return num_sockets; + } - int first_ipv4 = 1; - int first_ipv6 = 1; - for (PIP_ADAPTER_ADDRESSES adapter = adapter_address; adapter; adapter = adapter->Next) - { - if (adapter->TunnelType == TUNNEL_TYPE_TEREDO) - continue; - if (adapter->OperStatus != IfOperStatusUp) - continue; + int first_ipv4 = 1; + int first_ipv6 = 1; + for (PIP_ADAPTER_ADDRESSES adapter = adapter_address; adapter; + adapter = adapter->Next) { + if (adapter->TunnelType == TUNNEL_TYPE_TEREDO) continue; + if (adapter->OperStatus != IfOperStatusUp) continue; - for (IP_ADAPTER_UNICAST_ADDRESS *unicast = adapter->FirstUnicastAddress; unicast; - unicast = unicast->Next) - { - if (unicast->Address.lpSockaddr->sa_family == AF_INET) - { - struct sockaddr_in *saddr = (struct sockaddr_in *)unicast->Address.lpSockaddr; - if ((saddr->sin_addr.S_un.S_un_b.s_b1 != 127) || - (saddr->sin_addr.S_un.S_un_b.s_b2 != 0) || - (saddr->sin_addr.S_un.S_un_b.s_b3 != 0) || - (saddr->sin_addr.S_un.S_un_b.s_b4 != 1)) - { - int log_addr = 0; - if (first_ipv4) - { - service_address_ipv4 = *saddr; - first_ipv4 = 0; - log_addr = 1; - } - has_ipv4 = 1; - if (num_sockets < max_sockets) - { - saddr->sin_port = htons((unsigned short)port); - int sock = mdns_socket_open_ipv4(saddr); - if (sock >= 0) - { - sockets[num_sockets++] = sock; - log_addr = 1; - } - else - { - log_addr = 0; - } - } - if (log_addr) - { - char buffer[128]; - mdns_string_t addr = ipv4_address_to_string(buffer, sizeof(buffer), saddr, - sizeof(struct sockaddr_in)); - // printf("Local IPv4 address: %.*s\n", MDNS_STRING_FORMAT(addr)); - } + for (IP_ADAPTER_UNICAST_ADDRESS* unicast = adapter->FirstUnicastAddress; + unicast; unicast = unicast->Next) { + if (unicast->Address.lpSockaddr->sa_family == AF_INET) { + struct sockaddr_in* saddr = + (struct sockaddr_in*)unicast->Address.lpSockaddr; + if ((saddr->sin_addr.S_un.S_un_b.s_b1 != 127) || + (saddr->sin_addr.S_un.S_un_b.s_b2 != 0) || + (saddr->sin_addr.S_un.S_un_b.s_b3 != 0) || + (saddr->sin_addr.S_un.S_un_b.s_b4 != 1)) { + int log_addr = 0; + if (first_ipv4) { + service_address_ipv4 = *saddr; + first_ipv4 = 0; + log_addr = 1; + } + has_ipv4 = 1; + if (num_sockets < max_sockets) { + saddr->sin_port = htons((unsigned short)port); + int sock = mdns_socket_open_ipv4(saddr); + if (sock >= 0) { + sockets[num_sockets++] = sock; + log_addr = 1; + } else { + log_addr = 0; } } - else if (unicast->Address.lpSockaddr->sa_family == AF_INET6) - { - struct sockaddr_in6 *saddr = (struct sockaddr_in6 *)unicast->Address.lpSockaddr; - // Ignore link-local addresses - if (saddr->sin6_scope_id) - continue; - static const unsigned char localhost[] = {0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 1}; - static const unsigned char localhost_mapped[] = {0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0xff, 0xff, 0x7f, 0, 0, 1}; - if ((unicast->DadState == NldsPreferred) && - memcmp(saddr->sin6_addr.s6_addr, localhost, 16) && - memcmp(saddr->sin6_addr.s6_addr, localhost_mapped, 16)) - { - int log_addr = 0; - if (first_ipv6) - { - service_address_ipv6 = *saddr; - first_ipv6 = 0; - log_addr = 1; - } - has_ipv6 = 1; - if (num_sockets < max_sockets) - { - saddr->sin6_port = htons((unsigned short)port); - int sock = mdns_socket_open_ipv6(saddr); - if (sock >= 0) - { - sockets[num_sockets++] = sock; - log_addr = 1; - } - else - { - log_addr = 0; - } - } - if (log_addr) - { - char buffer[128]; - mdns_string_t addr = ipv6_address_to_string(buffer, sizeof(buffer), saddr, - sizeof(struct sockaddr_in6)); - // printf("Local IPv6 address: %.*s\n", MDNS_STRING_FORMAT(addr)); - } + if (log_addr) { + char buffer[128]; + mdns_string_t addr = ipv4_address_to_string( + buffer, sizeof(buffer), saddr, sizeof(struct sockaddr_in)); + // printf("Local IPv4 address: %.*s\n", MDNS_STRING_FORMAT(addr)); + } + } + } else if (unicast->Address.lpSockaddr->sa_family == AF_INET6) { + struct sockaddr_in6* saddr = + (struct sockaddr_in6*)unicast->Address.lpSockaddr; + // Ignore link-local addresses + if (saddr->sin6_scope_id) continue; + static const unsigned char localhost[] = {0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1}; + static const unsigned char localhost_mapped[] = { + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0xff, 0xff, 0x7f, 0, 0, 1}; + if ((unicast->DadState == NldsPreferred) && + memcmp(saddr->sin6_addr.s6_addr, localhost, 16) && + memcmp(saddr->sin6_addr.s6_addr, localhost_mapped, 16)) { + int log_addr = 0; + if (first_ipv6) { + service_address_ipv6 = *saddr; + first_ipv6 = 0; + log_addr = 1; + } + has_ipv6 = 1; + if (num_sockets < max_sockets) { + saddr->sin6_port = htons((unsigned short)port); + int sock = mdns_socket_open_ipv6(saddr); + if (sock >= 0) { + sockets[num_sockets++] = sock; + log_addr = 1; + } else { + log_addr = 0; } } + if (log_addr) { + char buffer[128]; + mdns_string_t addr = ipv6_address_to_string( + buffer, sizeof(buffer), saddr, sizeof(struct sockaddr_in6)); + // printf("Local IPv6 address: %.*s\n", MDNS_STRING_FORMAT(addr)); + } } } + } + } - free(adapter_address); + free(adapter_address); #else - struct ifaddrs *ifaddr = 0; - struct ifaddrs *ifa = 0; + struct ifaddrs* ifaddr = 0; + struct ifaddrs* ifa = 0; - if (getifaddrs(&ifaddr) < 0) - printf("Unable to get interface addresses\n"); + if (getifaddrs(&ifaddr) < 0) printf("Unable to get interface addresses\n"); - int first_ipv4 = 1; - int first_ipv6 = 1; - for (ifa = ifaddr; ifa; ifa = ifa->ifa_next) - { - if (!ifa->ifa_addr) - continue; - if (!(ifa->ifa_flags & IFF_UP) || !(ifa->ifa_flags & IFF_MULTICAST)) - continue; - if ((ifa->ifa_flags & IFF_LOOPBACK) || (ifa->ifa_flags & IFF_POINTOPOINT)) - continue; + int first_ipv4 = 1; + int first_ipv6 = 1; + for (ifa = ifaddr; ifa; ifa = ifa->ifa_next) { + if (!ifa->ifa_addr) continue; + if (!(ifa->ifa_flags & IFF_UP) || !(ifa->ifa_flags & IFF_MULTICAST)) + continue; + if ((ifa->ifa_flags & IFF_LOOPBACK) || (ifa->ifa_flags & IFF_POINTOPOINT)) + continue; - if (ifa->ifa_addr->sa_family == AF_INET) - { - struct sockaddr_in *saddr = (struct sockaddr_in *)ifa->ifa_addr; - if (saddr->sin_addr.s_addr != htonl(INADDR_LOOPBACK)) - { - int log_addr = 0; - if (first_ipv4) - { - service_address_ipv4 = *saddr; - first_ipv4 = 0; - log_addr = 1; - } - has_ipv4 = 1; - if (num_sockets < max_sockets) - { - saddr->sin_port = htons(port); - int sock = mdns_socket_open_ipv4(saddr); - if (sock >= 0) - { - sockets[num_sockets++] = sock; - log_addr = 1; - } - else - { - log_addr = 0; - } - } - if (log_addr) - { - char buffer[128]; - mdns_string_t addr = ipv4_address_to_string(buffer, sizeof(buffer), saddr, - sizeof(struct sockaddr_in)); - // printf("Local IPv4 address: %.*s\n", MDNS_STRING_FORMAT(addr)); - } + if (ifa->ifa_addr->sa_family == AF_INET) { + struct sockaddr_in* saddr = (struct sockaddr_in*)ifa->ifa_addr; + if (saddr->sin_addr.s_addr != htonl(INADDR_LOOPBACK)) { + int log_addr = 0; + if (first_ipv4) { + service_address_ipv4 = *saddr; + first_ipv4 = 0; + log_addr = 1; + } + has_ipv4 = 1; + if (num_sockets < max_sockets) { + saddr->sin_port = htons(port); + int sock = mdns_socket_open_ipv4(saddr); + if (sock >= 0) { + sockets[num_sockets++] = sock; + log_addr = 1; + } else { + log_addr = 0; } } - else if (ifa->ifa_addr->sa_family == AF_INET6) - { - struct sockaddr_in6 *saddr = (struct sockaddr_in6 *)ifa->ifa_addr; - // Ignore link-local addresses - if (saddr->sin6_scope_id) - continue; - static const unsigned char localhost[] = {0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 1}; - static const unsigned char localhost_mapped[] = {0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0xff, 0xff, 0x7f, 0, 0, 1}; - if (memcmp(saddr->sin6_addr.s6_addr, localhost, 16) && - memcmp(saddr->sin6_addr.s6_addr, localhost_mapped, 16)) - { - int log_addr = 0; - if (first_ipv6) - { - service_address_ipv6 = *saddr; - first_ipv6 = 0; - log_addr = 1; - } - has_ipv6 = 1; - if (num_sockets < max_sockets) - { - saddr->sin6_port = htons(port); - int sock = mdns_socket_open_ipv6(saddr); - if (sock >= 0) - { - sockets[num_sockets++] = sock; - log_addr = 1; - } - else - { - log_addr = 0; - } - } - if (log_addr) - { - char buffer[128]; - mdns_string_t addr = ipv6_address_to_string(buffer, sizeof(buffer), saddr, - sizeof(struct sockaddr_in6)); - // printf("Local IPv6 address: %.*s\n", MDNS_STRING_FORMAT(addr)); - } + if (log_addr) { + char buffer[128]; + mdns_string_t addr = ipv4_address_to_string( + buffer, sizeof(buffer), saddr, sizeof(struct sockaddr_in)); + // printf("Local IPv4 address: %.*s\n", MDNS_STRING_FORMAT(addr)); + } + } + } else if (ifa->ifa_addr->sa_family == AF_INET6) { + struct sockaddr_in6* saddr = (struct sockaddr_in6*)ifa->ifa_addr; + // Ignore link-local addresses + if (saddr->sin6_scope_id) continue; + static const unsigned char localhost[] = {0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1}; + static const unsigned char localhost_mapped[] = { + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0xff, 0xff, 0x7f, 0, 0, 1}; + if (memcmp(saddr->sin6_addr.s6_addr, localhost, 16) && + memcmp(saddr->sin6_addr.s6_addr, localhost_mapped, 16)) { + int log_addr = 0; + if (first_ipv6) { + service_address_ipv6 = *saddr; + first_ipv6 = 0; + log_addr = 1; + } + has_ipv6 = 1; + if (num_sockets < max_sockets) { + saddr->sin6_port = htons(port); + int sock = mdns_socket_open_ipv6(saddr); + if (sock >= 0) { + sockets[num_sockets++] = sock; + log_addr = 1; + } else { + log_addr = 0; } } + if (log_addr) { + char buffer[128]; + mdns_string_t addr = ipv6_address_to_string( + buffer, sizeof(buffer), saddr, sizeof(struct sockaddr_in6)); + // printf("Local IPv6 address: %.*s\n", MDNS_STRING_FORMAT(addr)); + } } + } + } - freeifaddrs(ifaddr); + freeifaddrs(ifaddr); #endif - return num_sockets; - } - } -} \ No newline at end of file + return num_sockets; +} +} // namespace zeroconf +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/discovery_impl.hh b/sdk/src/discovery_impl.hh index acb5522..178c92c 100644 --- a/sdk/src/discovery_impl.hh +++ b/sdk/src/discovery_impl.hh @@ -1,40 +1,35 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once - - -#include #include -#include +#include #include -namespace lebai -{ - namespace zeroconf - { - class Discovery::DiscoveryImpl - { - public: - DiscoveryImpl(); - virtual ~DiscoveryImpl(); - std::vector resolve(); - private: - void send_mdns_query(mdns_query_t* query, size_t count); - int open_client_sockets(int* sockets, int max_sockets, int port); - const std::string PTR_ = "_lebai._tcp.local"; - }; - } // namespace zeroconf -} \ No newline at end of file +namespace lebai { +namespace zeroconf { +class Discovery::DiscoveryImpl { + public: + DiscoveryImpl(); + virtual ~DiscoveryImpl(); + std::vector resolve(); + + private: + void send_mdns_query(mdns_query_t* query, size_t count); + int open_client_sockets(int* sockets, int max_sockets, int port); + const std::string PTR_ = "_lebai._tcp.local"; +}; +} // namespace zeroconf +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/jsonrpc_connector.cc b/sdk/src/jsonrpc_connector.cc index c609981..5662bf8 100755 --- a/sdk/src/jsonrpc_connector.cc +++ b/sdk/src/jsonrpc_connector.cc @@ -14,165 +14,154 @@ * limitations under the License. */ -#include "jsonrpc_connector.hh" - #include #include #include +#include "jsonrpc_connector.hh" #include "protos/utils.hh" -namespace lebai -{ +namespace lebai { - JSONRpcConnector::JSONRpcConnector(const std::string &ip, uint16_t port) - { - jsonrpc_id_ = 0; - std::string url = "ws://" + ip + ":" + std::to_string(port); - id_ = endpoint_.connect(url); - } - JSONRpcConnector::~JSONRpcConnector() {} +JSONRpcConnector::JSONRpcConnector(const std::string &ip, uint16_t port) { + jsonrpc_id_ = 0; + std::string url = "ws://" + ip + ":" + std::to_string(port); + id_ = endpoint_.connect(url); +} +JSONRpcConnector::~JSONRpcConnector() {} - // int JSONRpcConnector::Call(const std::string & method, rapidjson::Value & req_data, rapidjson::Value & resp_data) - // { - // rapidjson::Document d; - // rapidjson::Value req; - // req.SetObject(); - // req.AddMember("jsonrpc", "2.0", d.GetAllocator()); - // // req.AddMember("id", jsonrpc_id_++, d.GetAllocator()); - // rapidjson::Value method_value; - // method_value.SetString(method.c_str(), method.size(), d.GetAllocator()); - // req.AddMember("method", method_value, d.GetAllocator()); - // req.AddMember("params", req_data, d.GetAllocator()); - // rapidjson::StringBuffer buffer; - // rapidjson::Writer writer(buffer); - // req.Accept(writer); - // std::string req_str = buffer.GetString(); - // if(GetConnectionStatus() != kOpen) - // { - // return -1; - // } - // // std::cout << "req_str: " << req_str << std::endl; - // endpoint_.send(id_, req_str); - // auto const & resp_str = endpoint_.get_metadata(id_)->GetMessageStr(); - // // std::cout<<"resp_str: "<(resp_str.c_str()); - // rapidjson::Value::MemberIterator iter = d.FindMember("result"); - // if(iter == d.MemberEnd()) - // { - // return -1; - // } - // resp_data = iter->value; - // return 0; - // } +// int JSONRpcConnector::Call(const std::string & method, rapidjson::Value & +// req_data, rapidjson::Value & resp_data) +// { +// rapidjson::Document d; +// rapidjson::Value req; +// req.SetObject(); +// req.AddMember("jsonrpc", "2.0", d.GetAllocator()); +// // req.AddMember("id", jsonrpc_id_++, d.GetAllocator()); +// rapidjson::Value method_value; +// method_value.SetString(method.c_str(), method.size(), d.GetAllocator()); +// req.AddMember("method", method_value, d.GetAllocator()); +// req.AddMember("params", req_data, d.GetAllocator()); +// rapidjson::StringBuffer buffer; +// rapidjson::Writer writer(buffer); +// req.Accept(writer); +// std::string req_str = buffer.GetString(); +// if(GetConnectionStatus() != kOpen) +// { +// return -1; +// } +// // std::cout << "req_str: " << req_str << std::endl; +// endpoint_.send(id_, req_str); +// auto const & resp_str = endpoint_.get_metadata(id_)->GetMessageStr(); +// // std::cout<<"resp_str: "<(resp_str.c_str()); +// rapidjson::Value::MemberIterator iter = d.FindMember("result"); +// if(iter == d.MemberEnd()) +// { +// return -1; +// } +// resp_data = iter->value; +// return 0; +// } - // int JSONRpcConnector::CallString(int id, const std::string &method, const std::string & req_str, std::string * resp_str) - // { - // if(GetConnectionStatus() != kOpen) - // { - // return -1; - // } - // // std::string str_jsonrpc = "\"jsonrpc\":\"2.0\","; - // // std::string str_method = "\"method\":\"" + method + "\","; - // // std::string str_params = "\"params\":" + req_str + ","; - // // std::string str_id = "\"id\":" + std::to_string(jsonrpc_id_); - // // jsonrpc_id_++; - // std::string jsonrpc_req = "{\"jsonrpc\":\"2.0\",\"method\":\"" +method + - // "\",\"params\":"+req_str+",\"id\":"+ std::to_string(id)+ "}"; - // // str_method + str_params + str_id + "}"; - // // std::cerr<<"xxx jsonrpc_req: "<GetMessageStr(); - // *resp_str = jsonrpc_resp; +// int JSONRpcConnector::CallString(int id, const std::string &method, const +// std::string & req_str, std::string * resp_str) +// { +// if(GetConnectionStatus() != kOpen) +// { +// return -1; +// } +// // std::string str_jsonrpc = "\"jsonrpc\":\"2.0\","; +// // std::string str_method = "\"method\":\"" + method + "\","; +// // std::string str_params = "\"params\":" + req_str + ","; +// // std::string str_id = "\"id\":" + std::to_string(jsonrpc_id_); +// // jsonrpc_id_++; +// std::string jsonrpc_req = "{\"jsonrpc\":\"2.0\",\"method\":\"" +method + +// "\",\"params\":"+req_str+",\"id\":"+ std::to_string(id)+ "}"; +// // str_method + str_params + str_id + "}"; +// // std::cerr<<"xxx jsonrpc_req: "<GetMessageStr(); +// *resp_str = jsonrpc_resp; - // // std::cerr << "jsonrpc_resp: " << *resp_str << std::endl; - // } - // // {"jsonrpc": "2.0", "error": {"code": -32600, "message": "Invalid Request"}, "id": null} +// // std::cerr << "jsonrpc_resp: " << *resp_str << std::endl; +// } +// // {"jsonrpc": "2.0", "error": {"code": -32600, "message": "Invalid +// Request"}, "id": null} - // return 0; - // } +// return 0; +// } - // int JSONRpcConnector::CallRpc(const std::string & req_str, std::string * resp_str) - // { - // std::cout<<"req_str "<GetMessageStr(); - // int resp_id; - // ExtractJSONRpcRespString(*resp_str, resp_id, *resp_str); - // if(resp_id != id) - // { - // return -1; - // } - // std::cout<<"resp_str "<<*resp_str<<"\n"; - // } - // } +// int JSONRpcConnector::CallRpc(const std::string & req_str, std::string * +// resp_str) +// { +// std::cout<<"req_str "<GetMessageStr(); +// int resp_id; +// ExtractJSONRpcRespString(*resp_str, resp_id, *resp_str); +// if(resp_id != id) +// { +// return -1; +// } +// std::cout<<"resp_str "<<*resp_str<<"\n"; +// } +// } - int JSONRpcConnector::CallRpc(const std::string &method, const std::string &req_data_str, std::string *resp_data_str) - { - int call_jsonrpc_id = jsonrpc_id_++; - std::string jsonrpc_req; - std::string jsonrpc_resp; - jsonrpc_req = ToJSONRpcReqString(call_jsonrpc_id, method, req_data_str); - auto future = endpoint_.createFuture(id_, call_jsonrpc_id); - if (!endpoint_.send(id_, jsonrpc_req)) - { - endpoint_.deletePromise(id_, call_jsonrpc_id); - throw std::runtime_error("Send Jsonrpc request failed!"); - } - using namespace std::chrono_literals; - // TODO(@liufang) This corner case is not not good, need to be improved. - if (method != "wait_move") - { - // TODO(@liufang) Make the timeout configurable. - std::future_status status = future.wait_for(5s); - switch (status) - { +int JSONRpcConnector::CallRpc(const std::string &method, + const std::string &req_data_str, + std::string *resp_data_str) { + int call_jsonrpc_id = jsonrpc_id_++; + std::string jsonrpc_req; + std::string jsonrpc_resp; + jsonrpc_req = ToJSONRpcReqString(call_jsonrpc_id, method, req_data_str); + auto future = endpoint_.createFuture(id_, call_jsonrpc_id); + if (!endpoint_.send(id_, jsonrpc_req)) { + endpoint_.deletePromise(id_, call_jsonrpc_id); + throw std::runtime_error("Send Jsonrpc request failed!"); + } + using namespace std::chrono_literals; + // TODO(@liufang) This corner case is not not good, need to be improved. + if (method != "wait_move") { + // TODO(@liufang) Make the timeout configurable. + std::future_status status = future.wait_for(5s); + switch (status) { case std::future_status::deferred: case std::future_status::timeout: // std::cout << "timeout!\n"; throw std::runtime_error("No response from robot controller!"); case std::future_status::ready: break; - } } + } - auto resq_data = future.get(); - if (resp_data_str) - { - auto error_code = std::get<0>(resq_data); - if (error_code < 0) - { - throw std::runtime_error(std::get<1>(resq_data)); - } - *resp_data_str = std::get<1>(resq_data); + auto resq_data = future.get(); + if (resp_data_str) { + auto error_code = std::get<0>(resq_data); + if (error_code < 0) { + throw std::runtime_error(std::get<1>(resq_data)); } - return 0; + *resp_data_str = std::get<1>(resq_data); } + return 0; +} - JSONRpcConnector::ConnectionStatus JSONRpcConnector::GetConnectionStatus() - { - auto status = endpoint_.get_metadata(id_)->getStatus(); - if (status == "Open") - { - return kOpen; - } - else if (status == "Connecting") - { - return kConnecting; - } - else if (status == "Closed") - { - return kClosed; - } - else - { - return kFailed; - } +JSONRpcConnector::ConnectionStatus JSONRpcConnector::GetConnectionStatus() { + auto status = endpoint_.get_metadata(id_)->getStatus(); + if (status == "Open") { + return kOpen; + } else if (status == "Connecting") { + return kConnecting; + } else if (status == "Closed") { + return kClosed; + } else { + return kFailed; } +} -}; \ No newline at end of file +}; // namespace lebai \ No newline at end of file diff --git a/sdk/src/jsonrpc_connector.hh b/sdk/src/jsonrpc_connector.hh index 9b93c51..8295bd6 100644 --- a/sdk/src/jsonrpc_connector.hh +++ b/sdk/src/jsonrpc_connector.hh @@ -1,51 +1,49 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once - -#include "websocket.hh" #include #include +#include "websocket.hh" -namespace lebai -{ - class JSONRpcConnector - { - public: - enum ConnectionStatus - { - kConnecting, - kOpen, - kClosed, - kFailed, - }; - JSONRpcConnector(const std::string &ip, uint16_t port); - virtual ~JSONRpcConnector(); - // int Call(const std::string &method, rapidjson::Value &req_data, rapidjson::Value &resp_data); - // int CallString(int id, const std::string &method, const std::string & req_str, std::string * resp_str); - // /** - // int CallRpc(const std::string & req_str, std::string * resp_str); - int CallRpc(const std::string &method, const std::string & req_data_str, std::string * resp_data_str); - ConnectionStatus GetConnectionStatus(); - protected: - - WebSocketEndPoint endpoint_; - int id_; - std::atomic jsonrpc_id_; - // int jsonrpc_id_ = 0; +namespace lebai { +class JSONRpcConnector { + public: + enum ConnectionStatus { + kConnecting, + kOpen, + kClosed, + kFailed, }; + JSONRpcConnector(const std::string &ip, uint16_t port); + virtual ~JSONRpcConnector(); + // int Call(const std::string &method, rapidjson::Value &req_data, + // rapidjson::Value &resp_data); int CallString(int id, const std::string + // &method, const std::string & req_str, std::string * resp_str); + // /** + // int CallRpc(const std::string & req_str, std::string * resp_str); + int CallRpc(const std::string &method, const std::string &req_data_str, + std::string *resp_data_str); + ConnectionStatus GetConnectionStatus(); + + protected: + WebSocketEndPoint endpoint_; + int id_; + std::atomic jsonrpc_id_; + // int jsonrpc_id_ = 0; +}; -}; \ No newline at end of file +}; // namespace lebai \ No newline at end of file diff --git a/sdk/src/lua_robot.cc b/sdk/src/lua_robot.cc index 3c78c0f..caa8241 100644 --- a/sdk/src/lua_robot.cc +++ b/sdk/src/lua_robot.cc @@ -1,60 +1,47 @@ /** * Copyright 2022-2023 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ - + */ +#include #include #include "lua_robot_impl.hh" -#include - - namespace lebai { -namespace l_master -{ +namespace l_master { -LuaRobot::LuaRobot(std::string ip) -{ +LuaRobot::LuaRobot(std::string ip) { impl_ = std::make_unique(ip); } LuaRobot::~LuaRobot() {} +void LuaRobot::send(const std::string &lua_code) { impl_->send(lua_code); } -void LuaRobot::send(const std::string & lua_code) -{ - impl_->send(lua_code); -} - - -void LuaRobot::send(const std::vector & lua_codes) -{ +void LuaRobot::send(const std::vector &lua_codes) { std::string codes; codes = "program_begin(0)\n"; - for(auto &&code: lua_codes) - { - codes+=code+"\n"; + for (auto &&code : lua_codes) { + codes += code + "\n"; } codes += "program_end(0)\n"; impl_->send(codes); } -std::string LuaRobot::call(const std::string & lua_code) -{ - return impl_->call(lua_code); +std::string LuaRobot::call(const std::string &lua_code) { + return impl_->call(lua_code); } -} +} // namespace l_master -} // namespace l_master_sdk +} // namespace lebai diff --git a/sdk/src/lua_robot_impl.cc b/sdk/src/lua_robot_impl.cc index 7e42a12..37d2fdd 100644 --- a/sdk/src/lua_robot_impl.cc +++ b/sdk/src/lua_robot_impl.cc @@ -1,64 +1,57 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ -#include "lua_robot_impl.hh" #include #include +#include "lua_robot_impl.hh" -namespace lebai -{ - namespace l_master { - LuaRobot::LuaRobotImpl::LuaRobotImpl(const std::string &ip) - { - io_service_ = std::make_unique(); - connect(ip); - } - LuaRobot::LuaRobotImpl::~LuaRobotImpl() { - if(socket_) - { - socket_->close(); - } - } - int LuaRobot::LuaRobotImpl::connect(const std::string & ip) - { - asio::ip::tcp::resolver resolver(*io_service_); - auto endpoint_iterator = resolver.resolve({ip, "5180"}); - socket_ = std::make_unique(*io_service_); - doConnect(endpoint_iterator); - return 0; - } - void LuaRobot::LuaRobotImpl::send(const std::string & lua_code) - { - asio::write(*socket_,asio::buffer(lua_code.c_str(), lua_code.size())); - return; - } - - std::string LuaRobot::LuaRobotImpl::call(const std::string & lua_code) - { - std::string print_lua_code = "print(" + lua_code + ")"; - asio::write(*socket_,asio::buffer(print_lua_code.c_str(), print_lua_code.size())); - std::string ret; - // Max 1000 return string size. - ret.resize(1000); - size_t len = socket_->read_some(asio::buffer(ret)); - ret = ret.substr(0, len-2); - return ret; +namespace lebai { +namespace l_master { +LuaRobot::LuaRobotImpl::LuaRobotImpl(const std::string &ip) { + io_service_ = std::make_unique(); + connect(ip); +} +LuaRobot::LuaRobotImpl::~LuaRobotImpl() { + if (socket_) { + socket_->close(); } +} +int LuaRobot::LuaRobotImpl::connect(const std::string &ip) { + asio::ip::tcp::resolver resolver(*io_service_); + auto endpoint_iterator = resolver.resolve({ip, "5180"}); + socket_ = std::make_unique(*io_service_); + doConnect(endpoint_iterator); + return 0; +} +void LuaRobot::LuaRobotImpl::send(const std::string &lua_code) { + asio::write(*socket_, asio::buffer(lua_code.c_str(), lua_code.size())); + return; +} +std::string LuaRobot::LuaRobotImpl::call(const std::string &lua_code) { + std::string print_lua_code = "print(" + lua_code + ")"; + asio::write(*socket_, + asio::buffer(print_lua_code.c_str(), print_lua_code.size())); + std::string ret; + // Max 1000 return string size. + ret.resize(1000); + size_t len = socket_->read_some(asio::buffer(ret)); + ret = ret.substr(0, len - 2); + return ret; +} - - } -} \ No newline at end of file +} // namespace l_master +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/lua_robot_impl.hh b/sdk/src/lua_robot_impl.hh index dd62947..60de231 100644 --- a/sdk/src/lua_robot_impl.hh +++ b/sdk/src/lua_robot_impl.hh @@ -1,62 +1,54 @@ /** * Copyright 2022-2023 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once - +#include #include #include -#include -namespace lebai -{ - namespace l_master - { - class LuaRobot::LuaRobotImpl - { - public: - LuaRobotImpl(const::std::string &ip); - virtual ~LuaRobotImpl(); - int connect(const std::string & ip); - void send(const std::string & lua_code); - std::string call(const std::string & lua_code); - - protected: - void doConnect(asio::ip::tcp::resolver::iterator endpoint_iterator) - { - asio::async_connect(*socket_, endpoint_iterator, - [this](std::error_code ec, asio::ip::tcp::resolver::iterator) - { - if (!ec) - { - std::cerr<<"Connect ok.\n"; - } - else - { - std::cerr<<"Connect failed.\n"; - std::cerr<<"error code "< io_service_; - std::unique_ptr socket_; - // asio::deadline_timer deadline_; - bool connnected_ = false; - }; - } // namespace l_master -} \ No newline at end of file +namespace lebai { +namespace l_master { +class LuaRobot::LuaRobotImpl { + public: + LuaRobotImpl(const ::std::string &ip); + virtual ~LuaRobotImpl(); + int connect(const std::string &ip); + void send(const std::string &lua_code); + std::string call(const std::string &lua_code); + + protected: + void doConnect(asio::ip::tcp::resolver::iterator endpoint_iterator) { + asio::async_connect( + *socket_, endpoint_iterator, + [this](std::error_code ec, asio::ip::tcp::resolver::iterator) { + if (!ec) { + std::cerr << "Connect ok.\n"; + } else { + std::cerr << "Connect failed.\n"; + std::cerr << "error code " << ec.message() << "\n"; + } + }); + } + double timeout_ = 1.0; + const uint16_t port_ = 5180; + std::unique_ptr io_service_; + std::unique_ptr socket_; + // asio::deadline_timer deadline_; + bool connnected_ = false; +}; +} // namespace l_master +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/block.cc b/sdk/src/protos/block.cc index 242ebda..014ac9d 100644 --- a/sdk/src/protos/block.cc +++ b/sdk/src/protos/block.cc @@ -1,193 +1,109 @@ #include "block.hh" -namespace lebai -{ - namespace block - { - void Block::set_method(std::string method) - { - method_ = method; - } - std::string Block::method() - { - return method_; - } - std::string * Block::mutable_method() - { - return &method_; - } +namespace lebai { +namespace block { +void Block::set_method(std::string method) { method_ = method; } +std::string Block::method() { return method_; } +std::string *Block::mutable_method() { return &method_; } - void Block::set_param(std::string param) - { - param_ = param; - } - std::string Block::param() - { - return param_; - } - std::string * Block::mutable_param() - { - return ¶m_; - } +void Block::set_param(std::string param) { param_ = param; } +std::string Block::param() { return param_; } +std::string *Block::mutable_param() { return ¶m_; } - bool Block::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("method")) - { - std::string method_str = (std::string)(obj["method"].GetString()); - method_ = method_str; - } - if(obj.HasMember("param")) - { - std::string param_str = (std::string)(obj["param"].GetString()); - param_ = param_str; - } - return true; - } - bool Block::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("method"); - writer->String(method_.c_str()); - writer->Key("param"); - writer->String(param_.c_str()); - writer->EndObject(); - return true; - } - bool Block::IsNullJSONData() const - { - return false; - } +bool Block::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("method")) { + std::string method_str = (std::string)(obj["method"].GetString()); + method_ = method_str; + } + if (obj.HasMember("param")) { + std::string param_str = (std::string)(obj["param"].GetString()); + param_ = param_str; + } + return true; +} +bool Block::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("method"); + writer->String(method_.c_str()); + writer->Key("param"); + writer->String(param_.c_str()); + writer->EndObject(); + return true; +} +bool Block::IsNullJSONData() const { return false; } - void RunBlockRequest::set_name(std::string name) - { - name_ = name; - } - std::string RunBlockRequest::name() - { - return name_; - } - std::string *RunBlockRequest::mutable_name() - { - return &name_; - } +void RunBlockRequest::set_name(std::string name) { name_ = name; } +std::string RunBlockRequest::name() { return name_; } +std::string *RunBlockRequest::mutable_name() { return &name_; } - void RunBlockRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string RunBlockRequest::dir() - { - return dir_; - } - std::string *RunBlockRequest::mutable_dir() - { - return &dir_; - } - - bool RunBlockRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool RunBlockRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool RunBlockRequest::IsNullJSONData() const - { - return false; - } +void RunBlockRequest::set_dir(std::string dir) { dir_ = dir; } +std::string RunBlockRequest::dir() { return dir_; } +std::string *RunBlockRequest::mutable_dir() { return &dir_; } - void SaveBlockRequest::set_name(std::string name) - { - name_ = name; - } - std::string SaveBlockRequest::name() - { - return name_; - } - std::string *SaveBlockRequest::mutable_name() - { - return &name_; - } +bool RunBlockRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool RunBlockRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool RunBlockRequest::IsNullJSONData() const { return false; } - void SaveBlockRequest::set_data(Block data) - { - data_ = data; - } - Block SaveBlockRequest::data() - { - return data_; - } - Block *SaveBlockRequest::mutable_data() - { - return &data_; - } +void SaveBlockRequest::set_name(std::string name) { name_ = name; } +std::string SaveBlockRequest::name() { return name_; } +std::string *SaveBlockRequest::mutable_name() { return &name_; } - void SaveBlockRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string SaveBlockRequest::dir() - { - return dir_; - } - std::string *SaveBlockRequest::mutable_dir() - { - return &dir_; - } +void SaveBlockRequest::set_data(Block data) { data_ = data; } +Block SaveBlockRequest::data() { return data_; } +Block *SaveBlockRequest::mutable_data() { return &data_; } - bool SaveBlockRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("data")) - { - Block data; - data.FromJSONString(obj["data"].GetString()); - data_ = data; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool SaveBlockRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("data"); - writer->String(data_.ToJSONString().c_str()); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool SaveBlockRequest::IsNullJSONData() const - { - return false; - } - } -} \ No newline at end of file +void SaveBlockRequest::set_dir(std::string dir) { dir_ = dir; } +std::string SaveBlockRequest::dir() { return dir_; } +std::string *SaveBlockRequest::mutable_dir() { return &dir_; } + +bool SaveBlockRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("data")) { + Block data; + data.FromJSONString(obj["data"].GetString()); + data_ = data; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool SaveBlockRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("data"); + writer->String(data_.ToJSONString().c_str()); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool SaveBlockRequest::IsNullJSONData() const { return false; } +} // namespace block +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/block.hh b/sdk/src/protos/block.hh index bc90e01..a926cce 100644 --- a/sdk/src/protos/block.hh +++ b/sdk/src/protos/block.hh @@ -1,83 +1,78 @@ #pragma once #include "jsonbase.hh" -#include "db.hh" #include -#include -#include - -namespace lebai -{ - namespace block - { - - class Block : public JSONBase - { - public: - void set_method(std::string method); - std::string method(); - std::string * mutable_method(); - - void set_param(std::string param); - std::string param(); - std::string * mutable_param(); - - protected: - std::string method_; - std::string param_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class RunBlockRequest : public JSONBase - { - public: - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - std::string name_; - std::string dir_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SaveBlockRequest : public JSONBase - { - public: - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_data(Block data); - Block data(); - Block * mutable_data(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - std::string name_; - Block data_; - std::string dir_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - } -} \ No newline at end of file + +namespace lebai { +namespace block { + +class Block : public JSONBase { + public: + void set_method(std::string method); + std::string method(); + std::string *mutable_method(); + + void set_param(std::string param); + std::string param(); + std::string *mutable_param(); + + protected: + std::string method_; + std::string param_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class RunBlockRequest : public JSONBase { + public: + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + std::string name_; + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SaveBlockRequest : public JSONBase { + public: + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_data(Block data); + Block data(); + Block *mutable_data(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + std::string name_; + Block data_; + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +} // namespace block +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/claw.cc b/sdk/src/protos/claw.cc index cbb6bf6..25bf3b9 100644 --- a/sdk/src/protos/claw.cc +++ b/sdk/src/protos/claw.cc @@ -1,139 +1,74 @@ -#include #include "claw.hh" +namespace lebai { +namespace claw { -namespace lebai -{ - namespace claw - { - - void SetClawRequest::set_force(double force) - { - force_ = force; - } - double SetClawRequest::force() const - { - return force_; - } - double * SetClawRequest::mutable_force() - { - return &force_; - } - void SetClawRequest::set_amplitude(double amplitude) - { - amplitude_ = amplitude; - } - double SetClawRequest::amplitude() const - { - return amplitude_; - } - double * SetClawRequest::mutable_amplitude() - { - return &litude_; - } - // Deserialize - bool SetClawRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("force")) - { - force_ = obj["force"].GetDouble(); - } - if(obj.HasMember("amplitude")) - { - amplitude_ = obj["amplitude"].GetDouble(); - } - return true; - } - // Serialize - bool SetClawRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("force"); - writer->Double(force_); - writer->Key("amplitude"); - writer->Double(amplitude_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool SetClawRequest::IsNullJSONData() const - { - return false; - } - - - void Claw::set_force(double force) - { - force_ = force; - } - double Claw::force() const - { - return force_; - } - double * Claw::mutable_force() - { - return &force_; - } - void Claw::set_amplitude(double amplitude) - { - amplitude_ = amplitude; - } - double Claw::amplitude() const - { - return amplitude_; - } - double * Claw::mutable_amplitude() - { - return &litude_; - } - void Claw::set_hold_on(bool hold_on) - { - hold_on_ = hold_on; - } - bool Claw::hold_on() const - { - return hold_on_; - } - bool * Claw::mutable_hold_on() - { - return &hold_on_; - } - // Deserialize - bool Claw::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("force")) - { - force_ = obj["force"].GetDouble(); - } - if(obj.HasMember("amplitude")) - { - amplitude_ = obj["amplitude"].GetDouble(); - } - if(obj.HasMember("hold_on")) - { - hold_on_ = obj["hold_on"].GetBool(); - } - return true; - } - // Serialize - bool Claw::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("force"); - writer->Double(force_); - writer->Key("amplitude"); - writer->Double(amplitude_); - writer->Key("hold_on"); - writer->Bool(hold_on_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool Claw::IsNullJSONData() const - { - return false; - } - +void SetClawRequest::set_force(double force) { force_ = force; } +double SetClawRequest::force() const { return force_; } +double *SetClawRequest::mutable_force() { return &force_; } +void SetClawRequest::set_amplitude(double amplitude) { amplitude_ = amplitude; } +double SetClawRequest::amplitude() const { return amplitude_; } +double *SetClawRequest::mutable_amplitude() { return &litude_; } +// Deserialize +bool SetClawRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("force")) { + force_ = obj["force"].GetDouble(); + } + if (obj.HasMember("amplitude")) { + amplitude_ = obj["amplitude"].GetDouble(); + } + return true; +} +// Serialize +bool SetClawRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("force"); + writer->Double(force_); + writer->Key("amplitude"); + writer->Double(amplitude_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool SetClawRequest::IsNullJSONData() const { return false; } +void Claw::set_force(double force) { force_ = force; } +double Claw::force() const { return force_; } +double *Claw::mutable_force() { return &force_; } +void Claw::set_amplitude(double amplitude) { amplitude_ = amplitude; } +double Claw::amplitude() const { return amplitude_; } +double *Claw::mutable_amplitude() { return &litude_; } +void Claw::set_hold_on(bool hold_on) { hold_on_ = hold_on; } +bool Claw::hold_on() const { return hold_on_; } +bool *Claw::mutable_hold_on() { return &hold_on_; } +// Deserialize +bool Claw::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("force")) { + force_ = obj["force"].GetDouble(); } -} \ No newline at end of file + if (obj.HasMember("amplitude")) { + amplitude_ = obj["amplitude"].GetDouble(); + } + if (obj.HasMember("hold_on")) { + hold_on_ = obj["hold_on"].GetBool(); + } + return true; +} +// Serialize +bool Claw::Serialize(rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("force"); + writer->Double(force_); + writer->Key("amplitude"); + writer->Double(amplitude_); + writer->Key("hold_on"); + writer->Bool(hold_on_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool Claw::IsNullJSONData() const { return false; } + +} // namespace claw +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/claw.hh b/sdk/src/protos/claw.hh index b3f1bf5..55bb174 100644 --- a/sdk/src/protos/claw.hh +++ b/sdk/src/protos/claw.hh @@ -4,58 +4,55 @@ #include #include - -namespace lebai -{ - namespace claw - { - class SetClawRequest : public JSONBase - { - public: - void set_force(double force); - double force() const; - double * mutable_force(); - - void set_amplitude(double amplitude); - double amplitude() const; - double * mutable_amplitude(); - - protected: - double force_; - double amplitude_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class Claw : public JSONBase - { - public: - void set_force(double force); - double force() const; - double * mutable_force(); - - void set_amplitude(double amplitude); - double amplitude() const; - double * mutable_amplitude(); - - void set_hold_on(bool hold_on); - bool hold_on() const; - bool * mutable_hold_on(); - - protected: - double force_; - double amplitude_; - bool hold_on_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +namespace lebai { +namespace claw { +class SetClawRequest : public JSONBase { + public: + void set_force(double force); + double force() const; + double *mutable_force(); + + void set_amplitude(double amplitude); + double amplitude() const; + double *mutable_amplitude(); + + protected: + double force_; + double amplitude_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class Claw : public JSONBase { + public: + void set_force(double force); + double force() const; + double *mutable_force(); + + void set_amplitude(double amplitude); + double amplitude() const; + double *mutable_amplitude(); + + void set_hold_on(bool hold_on); + bool hold_on() const; + bool *mutable_hold_on(); + + protected: + double force_; + double amplitude_; + bool hold_on_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace claw +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/control.cc b/sdk/src/protos/control.cc index deb1900..2d2f273 100644 --- a/sdk/src/protos/control.cc +++ b/sdk/src/protos/control.cc @@ -1,766 +1,431 @@ -#include #include "control.hh" -namespace lebai -{ - namespace control - { - void StartTaskRequest::set_name(std::string name) - { - name_ = name; - } - std::string StartTaskRequest::name() - { - return name_; - } - std::string * StartTaskRequest::mutable_name() - { - return &name_; - } +namespace lebai { +namespace control { +void StartTaskRequest::set_name(std::string name) { name_ = name; } +std::string StartTaskRequest::name() { return name_; } +std::string *StartTaskRequest::mutable_name() { return &name_; } - void StartTaskRequest::set_is_parallel(bool is_parallel) - { - is_parallel_ = is_parallel; - } - bool StartTaskRequest::is_parallel() - { - return is_parallel_; - } - bool * StartTaskRequest::mutable_is_parallel() - { - return &is_parallel_; - } +void StartTaskRequest::set_is_parallel(bool is_parallel) { + is_parallel_ = is_parallel; +} +bool StartTaskRequest::is_parallel() { return is_parallel_; } +bool *StartTaskRequest::mutable_is_parallel() { return &is_parallel_; } - void StartTaskRequest::set_loop_to(unsigned int loop_to) - { - loop_to_ = loop_to; - } - unsigned int StartTaskRequest::loop_to() - { - return loop_to_; - } - unsigned int * StartTaskRequest::mutable_loop_to() - { - return &loop_to_; - } +void StartTaskRequest::set_loop_to(unsigned int loop_to) { loop_to_ = loop_to; } +unsigned int StartTaskRequest::loop_to() { return loop_to_; } +unsigned int *StartTaskRequest::mutable_loop_to() { return &loop_to_; } - void StartTaskRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string StartTaskRequest::dir() - { - return dir_; - } - std::string * StartTaskRequest::mutable_dir() - { - return &dir_; - } - - void StartTaskRequest::set_params(const std::vector & params) - { - params_ = params; - } - std::vector StartTaskRequest::params() - { - return params_; - } - std::vector * StartTaskRequest::mutable_params() - { - return ¶ms_; - } +void StartTaskRequest::set_dir(std::string dir) { dir_ = dir; } +std::string StartTaskRequest::dir() { return dir_; } +std::string *StartTaskRequest::mutable_dir() { return &dir_; } - bool StartTaskRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name_str = std::string(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("is_parallel")) - { - bool is_parallel_bool = bool(obj["is_parallel"].GetBool()); - is_parallel_ = is_parallel_bool; - } - if(obj.HasMember("loop_to")) - { - unsigned int loop_to_int = (unsigned int)(obj["loop_to"].GetUint()); - loop_to_ = loop_to_int; - } - if(obj.HasMember("dir")) - { - std::string dir_str = std::string(obj["dir"].GetString()); - dir_ = dir_str; - } - if(obj.HasMember("params")) - { - const rapidjson::Value& params = obj["params"]; - for (rapidjson::SizeType i = 0; i < params.Size(); i++) - { - std::string param_str = std::string(obj[i].GetString()); - params_.push_back(param_str); - } - } - return true; - } - bool StartTaskRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("is_parallel"); - writer->Bool(is_parallel_); - writer->Key("loop_to"); - writer->Uint(loop_to_); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->Key("kind"); - writer->Int(kind_); - writer->Key("params"); - writer->StartArray(); - for (auto& param : params_) - { - writer->String(param.c_str()); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool StartTaskRequest::IsNullJSONData() const - { - return false; - } +void StartTaskRequest::set_params(const std::vector ¶ms) { + params_ = params; +} +std::vector StartTaskRequest::params() { return params_; } +std::vector *StartTaskRequest::mutable_params() { + return ¶ms_; +} - void TaskIds::set_ids(std::vector ids) - { - ids_ = ids; - } - std::vector TaskIds::ids() - { - return ids_; - } - std::vector * TaskIds::mutable_ids() - { - return &ids_; - } - bool TaskIds::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("ids")) - { - const rapidjson::Value& ids = obj["ids"]; - for (rapidjson::SizeType i = 0; i < ids.Size(); i++) - { - unsigned int id_int = (unsigned int)(obj[i].GetUint()); - ids_.push_back(id_int); - } - } - return true; - } - bool TaskIds::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("ids"); - writer->StartArray(); - for (auto& id : ids_) - { - writer->Uint(id); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool TaskIds::IsNullJSONData() const - { - return false; - } +bool StartTaskRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name_str = std::string(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("is_parallel")) { + bool is_parallel_bool = bool(obj["is_parallel"].GetBool()); + is_parallel_ = is_parallel_bool; + } + if (obj.HasMember("loop_to")) { + unsigned int loop_to_int = (unsigned int)(obj["loop_to"].GetUint()); + loop_to_ = loop_to_int; + } + if (obj.HasMember("dir")) { + std::string dir_str = std::string(obj["dir"].GetString()); + dir_ = dir_str; + } + if (obj.HasMember("params")) { + const rapidjson::Value ¶ms = obj["params"]; + for (rapidjson::SizeType i = 0; i < params.Size(); i++) { + std::string param_str = std::string(obj[i].GetString()); + params_.push_back(param_str); + } + } + return true; +} +bool StartTaskRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("is_parallel"); + writer->Bool(is_parallel_); + writer->Key("loop_to"); + writer->Uint(loop_to_); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->Key("kind"); + writer->Int(kind_); + writer->Key("params"); + writer->StartArray(); + for (auto ¶m : params_) { + writer->String(param.c_str()); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool StartTaskRequest::IsNullJSONData() const { return false; } - void TaskIndex::set_id(unsigned int id) - { - id_ = id; - } - unsigned TaskIndex::id() - { - return id_; - } - unsigned int * TaskIndex::mutable_id() - { - return &id_; - } - bool TaskIndex::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("id")) - { - unsigned int id_int = (unsigned int)(obj["id"].GetUint()); - id_ = id_int; - } - return true; - } - bool TaskIndex::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("id"); - writer->Uint(id_); - writer->EndObject(); - return true; - } - bool TaskIndex::IsNullJSONData() const - { - return false; - } +void TaskIds::set_ids(std::vector ids) { ids_ = ids; } +std::vector TaskIds::ids() { return ids_; } +std::vector *TaskIds::mutable_ids() { return &ids_; } +bool TaskIds::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("ids")) { + const rapidjson::Value &ids = obj["ids"]; + for (rapidjson::SizeType i = 0; i < ids.Size(); i++) { + unsigned int id_int = (unsigned int)(obj[i].GetUint()); + ids_.push_back(id_int); + } + } + return true; +} +bool TaskIds::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("ids"); + writer->StartArray(); + for (auto &id : ids_) { + writer->Uint(id); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool TaskIds::IsNullJSONData() const { return false; } - void PauseRequest::set_id(unsigned int id) - { - id_ = id; - } - unsigned int PauseRequest::id() - { - return id_; - } - unsigned int * PauseRequest::mutable_id() - { - return &id_; - } +void TaskIndex::set_id(unsigned int id) { id_ = id; } +unsigned TaskIndex::id() { return id_; } +unsigned int *TaskIndex::mutable_id() { return &id_; } +bool TaskIndex::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("id")) { + unsigned int id_int = (unsigned int)(obj["id"].GetUint()); + id_ = id_int; + } + return true; +} +bool TaskIndex::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("id"); + writer->Uint(id_); + writer->EndObject(); + return true; +} +bool TaskIndex::IsNullJSONData() const { return false; } - void PauseRequest::set_time(unsigned long time) - { - time_ = time; - } - unsigned long PauseRequest::time() - { - return time_; - } - unsigned long * PauseRequest::mutable_time() - { - return &time_; - } +void PauseRequest::set_id(unsigned int id) { id_ = id; } +unsigned int PauseRequest::id() { return id_; } +unsigned int *PauseRequest::mutable_id() { return &id_; } - void PauseRequest::set_wait(bool wait) - { - wait_ = wait; - } - bool PauseRequest::wait() - { - return wait_; - } - bool * PauseRequest::mutable_wait() - { - return &wait_; - } +void PauseRequest::set_time(unsigned long time) { time_ = time; } +unsigned long PauseRequest::time() { return time_; } +unsigned long *PauseRequest::mutable_time() { return &time_; } - bool PauseRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("id")) - { - unsigned int id_int = (unsigned int)(obj["id"].GetUint()); - id_ = id_int; - } - if(obj.HasMember("time")) - { - unsigned long time_u64 = (unsigned long)(obj["time"].GetUint64()); - time_ = time_u64; - } - if(obj.HasMember("wait")) - { - bool wait_bool = (bool)(obj["wait"].GetBool()); - wait_ = wait_bool; - } - return true; - } - bool PauseRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("id"); - writer->Uint(id_); - writer->Key("time"); - writer->Uint64(time_); - writer->Key("wait"); - writer->Bool(wait_); - writer->EndObject(); - return true; - } - bool PauseRequest::IsNullJSONData() const - { - return false; - } - void Task::set_id(unsigned int id) - { - id_ = id; - } - unsigned int Task::id() - { - return id_; - } - unsigned int *Task::mutable_id() - { - return &id_; - } +void PauseRequest::set_wait(bool wait) { wait_ = wait; } +bool PauseRequest::wait() { return wait_; } +bool *PauseRequest::mutable_wait() { return &wait_; } - void Task::set_block_id(std::string block_id) - { - block_id_ = block_id; - } - std::string Task::block_id() - { - return block_id_; - } - std::string *Task::mutable_block_id() - { - return &block_id_; - } +bool PauseRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("id")) { + unsigned int id_int = (unsigned int)(obj["id"].GetUint()); + id_ = id_int; + } + if (obj.HasMember("time")) { + unsigned long time_u64 = (unsigned long)(obj["time"].GetUint64()); + time_ = time_u64; + } + if (obj.HasMember("wait")) { + bool wait_bool = (bool)(obj["wait"].GetBool()); + wait_ = wait_bool; + } + return true; +} +bool PauseRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("id"); + writer->Uint(id_); + writer->Key("time"); + writer->Uint64(time_); + writer->Key("wait"); + writer->Bool(wait_); + writer->EndObject(); + return true; +} +bool PauseRequest::IsNullJSONData() const { return false; } +void Task::set_id(unsigned int id) { id_ = id; } +unsigned int Task::id() { return id_; } +unsigned int *Task::mutable_id() { return &id_; } - void Task::set_state(TaskState state) - { - state_ = state; - } - TaskState Task::state() - { - return state_; - } - TaskState *Task::mutable_state() - { - return &state_; - } +void Task::set_block_id(std::string block_id) { block_id_ = block_id; } +std::string Task::block_id() { return block_id_; } +std::string *Task::mutable_block_id() { return &block_id_; } - void Task::set_loopc(unsigned int loopc) - { - loopc_ = loopc; - } - unsigned int Task::loopc() - { - return loopc_; - } - unsigned int *Task::mutable_loopc() - { - return &loopc_; - } +void Task::set_state(TaskState state) { state_ = state; } +TaskState Task::state() { return state_; } +TaskState *Task::mutable_state() { return &state_; } - void Task::set_loopt(unsigned int loopt) - { - loopt_ = loopt; - } - unsigned int Task::loopt() - { - return loopt_; - } - unsigned int *Task::mutable_loopt() - { - return &loopt_; - } +void Task::set_loopc(unsigned int loopc) { loopc_ = loopc; } +unsigned int Task::loopc() { return loopc_; } +unsigned int *Task::mutable_loopc() { return &loopc_; } - void Task::set_is_parallel(bool is_parallel) - { - is_parallel_ = is_parallel; - } - bool Task::is_parallel() - { - return is_parallel_; - } - bool *Task::mutable_is_parallel() - { - return &is_parallel_; - } +void Task::set_loopt(unsigned int loopt) { loopt_ = loopt; } +unsigned int Task::loopt() { return loopt_; } +unsigned int *Task::mutable_loopt() { return &loopt_; } - void Task::set_is_simu(bool is_simu) - { - is_simu_ = is_simu; - } - bool Task::is_simu() - { - return is_simu_; - } - bool *Task::mutable_is_simu() - { - return &is_simu_; - } +void Task::set_is_parallel(bool is_parallel) { is_parallel_ = is_parallel; } +bool Task::is_parallel() { return is_parallel_; } +bool *Task::mutable_is_parallel() { return &is_parallel_; } - void Task::set_out(std::string out) - { - out_ = out; - } - std::string Task::out() - { - return out_; - } - std::string *Task::mutable_out() - { - return &out_; - } +void Task::set_is_simu(bool is_simu) { is_simu_ = is_simu; } +bool Task::is_simu() { return is_simu_; } +bool *Task::mutable_is_simu() { return &is_simu_; } - void Task::set_started_at(std::string started_at) - { - started_at_ = started_at; - } - std::string Task::started_at() - { - return started_at_; - } - std::string *Task::mutable_started_at() - { - return &started_at_; - } +void Task::set_out(std::string out) { out_ = out; } +std::string Task::out() { return out_; } +std::string *Task::mutable_out() { return &out_; } - void Task::set_ended_at(std::string ended_at) - { - ended_at_ = ended_at; - } - std::string Task::ended_at() - { - return ended_at_; - } - std::string *Task::mutable_ended_at() - { - return &ended_at_; - } +void Task::set_started_at(std::string started_at) { started_at_ = started_at; } +std::string Task::started_at() { return started_at_; } +std::string *Task::mutable_started_at() { return &started_at_; } - void Task::set_pause_at(std::string pause_at) - { - pause_at_ = pause_at; - } - std::string Task::pause_at() - { - return pause_at_; - } - std::string *Task::mutable_pause_at() - { - return &pause_at_; - } +void Task::set_ended_at(std::string ended_at) { ended_at_ = ended_at; } +std::string Task::ended_at() { return ended_at_; } +std::string *Task::mutable_ended_at() { return &ended_at_; } - void Task::set_pre_pause(unsigned int pre_pause) - { - pre_pause_ = pre_pause; - } - unsigned int Task::pre_pause() - { - return pre_pause_; - } - unsigned int *Task::mutable_pre_pause() - { - return &pre_pause_; - } +void Task::set_pause_at(std::string pause_at) { pause_at_ = pause_at; } +std::string Task::pause_at() { return pause_at_; } +std::string *Task::mutable_pause_at() { return &pause_at_; } - void Task::set_kind(TaskKind kind) - { - kind_ = kind; - } - TaskKind Task::kind() - { - return kind_; - } - TaskKind *Task::mutable_kind() - { - return &kind_; - } +void Task::set_pre_pause(unsigned int pre_pause) { pre_pause_ = pre_pause; } +unsigned int Task::pre_pause() { return pre_pause_; } +unsigned int *Task::mutable_pre_pause() { return &pre_pause_; } - void Task::set_dir(std::string dir) - { - dir_ = dir; - } - std::string Task::dir() - { - return dir_; - } - std::string *Task::mutable_dir() - { - return &dir_; - } +void Task::set_kind(TaskKind kind) { kind_ = kind; } +TaskKind Task::kind() { return kind_; } +TaskKind *Task::mutable_kind() { return &kind_; } - void Task::set_name(std::string name) - { - name_ = name; - } - std::string Task::name() - { - return name_; - } - std::string *Task::mutable_name() - { - return &name_; - } +void Task::set_dir(std::string dir) { dir_ = dir; } +std::string Task::dir() { return dir_; } +std::string *Task::mutable_dir() { return &dir_; } - void Task::set_params(std::vector params) - { - params_ = params; - } - std::vector Task::params() - { - return params_; - } - std::vector *Task::mutable_params() - { - return ¶ms_; - } - bool Task::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("id")) - { - id_ = (unsigned int)(obj["id"].GetUint()); - } - if(obj.HasMember("block_id")) - { - block_id_ = (std::string)(obj["block_id"].GetString()); - } - if(obj.HasMember("state")) - { - std::string state = (std::string)(obj["state"].GetString()); - if(state == "WAIT") - { - state_ = TaskState::WAIT; - }else if(state == "NONE") - { - state_ = TaskState::NONE; - }else if(state == "RUNNING") - { - state_ = TaskState::RUNNING; - }else if(state == "PAUSE") - { - state_ = TaskState::PAUSE; - }else if(state == "SUCCESS") - { - state_ = TaskState::SUCCESS; - }else if(state == "INTERRUPT") - { - state_ = TaskState::INTERRUPT; - }else if(state == "FAIL") - { - state_ = TaskState::FAIL; - }else if(state == "INTERRUPTING") - { - state_ = TaskState::INTERRUPTING; - } - } - if(obj.HasMember("loop_count")) - { - loopc_ = (unsigned int)(obj["loop_count"].GetUint()); - } - if(obj.HasMember("loop_to")) - { - loopt_ = (unsigned int)(obj["loop_to"].GetUint()); - } - if(obj.HasMember("is_parallel")) - { - is_parallel_ = bool(obj["is_parallel"].GetBool()); - } - if(obj.HasMember("is_simu")) - { - is_simu_ = bool(obj["is_simu"].GetBool()); - } - if(obj.HasMember("stdout")) - { - out_ = (std::string)(obj["stdout"].GetString()); - } - if(obj.HasMember("started_at")) - { - started_at_ = (std::string)(obj["started_at"].GetString()); - } - if(obj.HasMember("ended_at")) - { - ended_at_ = (std::string)(obj["ended_at"].GetString()); - } - if(obj.HasMember("pause_at")) - { - pause_at_ = (std::string)(obj["pause_at"].GetString()); - } - if(obj.HasMember("pre_pause")) - { - pre_pause_ = (unsigned int)(obj["pre_pause"].GetUint()); - } - if(obj.HasMember("kind")) - { - std::string kind = (std::string)(obj["kind"].GetString()); - if(kind == "LUA") - { - kind_ = TaskKind::LUA; - }else if(kind == "APP") - { - kind_ = TaskKind::APP; - } - } - if(obj.HasMember("dir")) - { - dir_ = (std::string)(obj["dir"].GetString()); - } - if(obj.HasMember("name")) - { - name_ = (std::string)(obj["name"].GetString()); - } - if(obj.HasMember("params")) - { - std::vector params; - for(auto i = obj["params"].GetArray().Begin();i != obj["params"].GetArray().End();i++) - { - params.push_back(i->GetString()); - } - params_ = params; - } - return true; - } - bool Task::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("id"); - writer->Uint(id_); - writer->Key("block_id"); - writer->String(block_id_.c_str()); - writer->Key("state"); - switch(state_) - { - case TaskState::NONE: - writer->String("NONE"); - break; - case TaskState::WAIT: - writer->String("WAIT"); - break; - case TaskState::RUNNING: - writer->String("RUNNING"); - break; - case TaskState::PAUSE: - writer->String("PAUSE"); - break; - case TaskState::SUCCESS: - writer->String("SUCCESS"); - break; - case TaskState::INTERRUPT: - writer->String("INTERRUPT"); - break; - case TaskState::FAIL: - writer->String("FAIL"); - break; - case TaskState::INTERRUPTING: - writer->String("INTERRUPTING"); - break; - default: - writer->String("nil"); - break; - }; - writer->Key("loop_count"); - writer->Uint(loopc_); - writer->Key("loop_to"); - writer->Uint(loopt_); - writer->Key("is_parallel"); - writer->Bool(is_parallel_); - writer->Key("is_simu"); - writer->Bool(is_simu_); - writer->Key("stdout"); - writer->String(out_.c_str()); - writer->Key("started_at"); - writer->String(started_at_.c_str()); - writer->Key("ended_at"); - writer->String(ended_at_.c_str()); - writer->Key("pause_at"); - writer->String(pause_at_.c_str()); - writer->Key("kind"); - switch(kind_) - { - case TaskKind::APP: - writer->String("APP"); - break; - case TaskKind::LUA: - writer->String("LUA"); - break; - } - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("params"); - writer->StartArray(); - for(auto i:params_) - { - writer->String(i.c_str()); - } - writer->EndArray(); - writer->EndObject(); - return true; +void Task::set_name(std::string name) { name_ = name; } +std::string Task::name() { return name_; } +std::string *Task::mutable_name() { return &name_; } - } - bool Task::IsNullJSONData() const - { - return false; - } +void Task::set_params(std::vector params) { params_ = params; } +std::vector Task::params() { return params_; } +std::vector *Task::mutable_params() { return ¶ms_; } +bool Task::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("id")) { + id_ = (unsigned int)(obj["id"].GetUint()); + } + if (obj.HasMember("block_id")) { + block_id_ = (std::string)(obj["block_id"].GetString()); + } + if (obj.HasMember("state")) { + std::string state = (std::string)(obj["state"].GetString()); + if (state == "WAIT") { + state_ = TaskState::WAIT; + } else if (state == "NONE") { + state_ = TaskState::NONE; + } else if (state == "RUNNING") { + state_ = TaskState::RUNNING; + } else if (state == "PAUSE") { + state_ = TaskState::PAUSE; + } else if (state == "SUCCESS") { + state_ = TaskState::SUCCESS; + } else if (state == "INTERRUPT") { + state_ = TaskState::INTERRUPT; + } else if (state == "FAIL") { + state_ = TaskState::FAIL; + } else if (state == "INTERRUPTING") { + state_ = TaskState::INTERRUPTING; + } + } + if (obj.HasMember("loop_count")) { + loopc_ = (unsigned int)(obj["loop_count"].GetUint()); + } + if (obj.HasMember("loop_to")) { + loopt_ = (unsigned int)(obj["loop_to"].GetUint()); + } + if (obj.HasMember("is_parallel")) { + is_parallel_ = bool(obj["is_parallel"].GetBool()); + } + if (obj.HasMember("is_simu")) { + is_simu_ = bool(obj["is_simu"].GetBool()); + } + if (obj.HasMember("stdout")) { + out_ = (std::string)(obj["stdout"].GetString()); + } + if (obj.HasMember("started_at")) { + started_at_ = (std::string)(obj["started_at"].GetString()); + } + if (obj.HasMember("ended_at")) { + ended_at_ = (std::string)(obj["ended_at"].GetString()); + } + if (obj.HasMember("pause_at")) { + pause_at_ = (std::string)(obj["pause_at"].GetString()); + } + if (obj.HasMember("pre_pause")) { + pre_pause_ = (unsigned int)(obj["pre_pause"].GetUint()); + } + if (obj.HasMember("kind")) { + std::string kind = (std::string)(obj["kind"].GetString()); + if (kind == "LUA") { + kind_ = TaskKind::LUA; + } else if (kind == "APP") { + kind_ = TaskKind::APP; + } + } + if (obj.HasMember("dir")) { + dir_ = (std::string)(obj["dir"].GetString()); + } + if (obj.HasMember("name")) { + name_ = (std::string)(obj["name"].GetString()); + } + if (obj.HasMember("params")) { + std::vector params; + for (auto i = obj["params"].GetArray().Begin(); + i != obj["params"].GetArray().End(); i++) { + params.push_back(i->GetString()); + } + params_ = params; + } + return true; +} +bool Task::Serialize(rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("id"); + writer->Uint(id_); + writer->Key("block_id"); + writer->String(block_id_.c_str()); + writer->Key("state"); + switch (state_) { + case TaskState::NONE: + writer->String("NONE"); + break; + case TaskState::WAIT: + writer->String("WAIT"); + break; + case TaskState::RUNNING: + writer->String("RUNNING"); + break; + case TaskState::PAUSE: + writer->String("PAUSE"); + break; + case TaskState::SUCCESS: + writer->String("SUCCESS"); + break; + case TaskState::INTERRUPT: + writer->String("INTERRUPT"); + break; + case TaskState::FAIL: + writer->String("FAIL"); + break; + case TaskState::INTERRUPTING: + writer->String("INTERRUPTING"); + break; + default: + writer->String("nil"); + break; + }; + writer->Key("loop_count"); + writer->Uint(loopc_); + writer->Key("loop_to"); + writer->Uint(loopt_); + writer->Key("is_parallel"); + writer->Bool(is_parallel_); + writer->Key("is_simu"); + writer->Bool(is_simu_); + writer->Key("stdout"); + writer->String(out_.c_str()); + writer->Key("started_at"); + writer->String(started_at_.c_str()); + writer->Key("ended_at"); + writer->String(ended_at_.c_str()); + writer->Key("pause_at"); + writer->String(pause_at_.c_str()); + writer->Key("kind"); + switch (kind_) { + case TaskKind::APP: + writer->String("APP"); + break; + case TaskKind::LUA: + writer->String("LUA"); + break; + } + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("params"); + writer->StartArray(); + for (auto i : params_) { + writer->String(i.c_str()); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool Task::IsNullJSONData() const { return false; } - void Exec::set_id(unsigned int id) - { - id_ = id; - } - unsigned int Exec::id() - { - return id_; - } - unsigned int *Exec::mutable_id() - { - return &id_; - } - bool Exec::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("id")) - { - id_ = (unsigned int)(obj["id"].GetUint()); - } - return true; - } - bool Exec::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("id"); - writer->Uint(id_); - writer->EndObject(); - return true; - } - bool Exec::IsNullJSONData() const - { - return false; - } +void Exec::set_id(unsigned int id) { id_ = id; } +unsigned int Exec::id() { return id_; } +unsigned int *Exec::mutable_id() { return &id_; } +bool Exec::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("id")) { + id_ = (unsigned int)(obj["id"].GetUint()); + } + return true; +} +bool Exec::Serialize(rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("id"); + writer->Uint(id_); + writer->EndObject(); + return true; +} +bool Exec::IsNullJSONData() const { return false; } - void HookResponse::set_success(unsigned int success) - { - success_ = success; - } - unsigned int HookResponse::success() - { - return success_; - } - unsigned int *HookResponse::mutable_success() - { - return &success_; - } +void HookResponse::set_success(unsigned int success) { success_ = success; } +unsigned int HookResponse::success() { return success_; } +unsigned int *HookResponse::mutable_success() { return &success_; } - void HookResponse::set_error(std::string error) - { - error_ = error; - } - std::string HookResponse::error() - { - return error_; - } - std::string *HookResponse::mutable_error() - { - return &error_; - } - bool HookResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("success")) - { - success_ = bool(obj["success"].GetBool()); - } - if(obj.HasMember("error")) - { - error_ = (std::string)(obj["error"].GetString()); - } - return true; - } - bool HookResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("success"); - writer->Bool(success_); - writer->Key("error"); - writer->String(error_.c_str()); - writer->EndObject(); - return true; - } - bool HookResponse::IsNullJSONData() const - { - return false; - } - } -} \ No newline at end of file +void HookResponse::set_error(std::string error) { error_ = error; } +std::string HookResponse::error() { return error_; } +std::string *HookResponse::mutable_error() { return &error_; } +bool HookResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("success")) { + success_ = bool(obj["success"].GetBool()); + } + if (obj.HasMember("error")) { + error_ = (std::string)(obj["error"].GetString()); + } + return true; +} +bool HookResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("success"); + writer->Bool(success_); + writer->Key("error"); + writer->String(error_.c_str()); + writer->EndObject(); + return true; +} +bool HookResponse::IsNullJSONData() const { return false; } +} // namespace control +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/control.hh b/sdk/src/protos/control.hh index 27af1b8..f011515 100644 --- a/sdk/src/protos/control.hh +++ b/sdk/src/protos/control.hh @@ -6,247 +6,245 @@ #include #include -namespace lebai -{ - namespace control - { - enum TaskKind - { - LUA = 0, - APP = 10, - }; - - enum TaskState - { - NONE = 0, - RUNNING = 1, - PAUSE = 2, - SUCCESS = 3, - INTERRUPT = 4, - FAIL = 5, - WAIT = 10, - INTERRUPTING = 14, - }; - - class StartTaskRequest : public JSONBase - { - public: - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_is_parallel(bool is_main); - bool is_parallel(); - bool * mutable_is_parallel(); - - void set_loop_to(unsigned int loop_to); - unsigned int loop_to(); - unsigned int * mutable_loop_to(); - - void set_dir(std::string name); - std::string dir(); - std::string * mutable_dir(); - - void set_params(const std::vector & name); - std::vector params(); - std::vector * mutable_params(); - - - protected: - std::string name_; - bool is_parallel_; - unsigned int loop_to_; - std::string dir_; - TaskKind kind_ = TaskKind::LUA; - std::vector params_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class TaskIds : public JSONBase - { - public: - void set_ids(std::vector ids); - std::vector ids(); - std::vector * mutable_ids(); - - protected: - std::vector ids_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class TaskIndex : public JSONBase - { - public: - void set_id(unsigned int id); - unsigned int id(); - unsigned int * mutable_id(); - - protected: - unsigned int id_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class Task : public JSONBase - { - public: - void set_id(unsigned int id); - unsigned int id(); - unsigned int * mutable_id(); - - void set_block_id(std::string block_id); - std::string block_id(); - std::string * mutable_block_id(); - - void set_state(TaskState state); - TaskState state(); - TaskState * mutable_state(); - - void set_loopc(unsigned int loopc); - unsigned int loopc(); - unsigned int * mutable_loopc(); - - void set_loopt(unsigned int loopt); - unsigned int loopt(); - unsigned int * mutable_loopt(); - - void set_is_parallel(bool is_parallel); - bool is_parallel(); - bool * mutable_is_parallel(); - - void set_is_simu(bool is_simu); - bool is_simu(); - bool * mutable_is_simu(); - - void set_out(std::string out); - std::string out(); - std::string * mutable_out(); - - void set_started_at(std::string started_at); - std::string started_at(); - std::string * mutable_started_at(); - - void set_ended_at(std::string ended_at); - std::string ended_at(); - std::string * mutable_ended_at(); - - void set_pause_at(std::string pause_at); - std::string pause_at(); - std::string * mutable_pause_at(); - - void set_pre_pause(unsigned int pre_pause); - unsigned int pre_pause(); - unsigned int * mutable_pre_pause(); - - void set_kind(TaskKind kind); - TaskKind kind(); - TaskKind * mutable_kind(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_params(std::vector params); - std::vector params(); - std::vector * mutable_params(); - - protected: - unsigned int id_; - std::string block_id_; - TaskState state_; - unsigned int loopc_; - unsigned int loopt_; - bool is_parallel_; - bool is_simu_; - std::string out_; - std::string started_at_; - std::string ended_at_; - std::string pause_at_; - unsigned int pre_pause_; - TaskKind kind_; - std::string dir_; - std::string name_; - std::vector params_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class PauseRequest : public JSONBase - { - public: - void set_id(unsigned int id); - unsigned int id(); - unsigned int * mutable_id(); - - void set_time(unsigned long time); - unsigned long time(); - unsigned long * mutable_time(); - - void set_wait(bool wait); - bool wait(); - bool * mutable_wait(); - - protected: - unsigned int id_; - unsigned long time_; - bool wait_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class Exec : public JSONBase - { - public: - void set_id(unsigned int id); - unsigned int id(); - unsigned int * mutable_id(); - - protected: - unsigned int id_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class HookResponse : public JSONBase - { - public: - void set_success(unsigned int success); - unsigned int success(); - unsigned int * mutable_success(); - - void set_error(std::string error); - std::string error(); - std::string * mutable_error(); - - protected: - unsigned int success_; - std::string error_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +namespace lebai { +namespace control { +enum TaskKind { + LUA = 0, + APP = 10, +}; + +enum TaskState { + NONE = 0, + RUNNING = 1, + PAUSE = 2, + SUCCESS = 3, + INTERRUPT = 4, + FAIL = 5, + WAIT = 10, + INTERRUPTING = 14, +}; + +class StartTaskRequest : public JSONBase { + public: + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_is_parallel(bool is_main); + bool is_parallel(); + bool *mutable_is_parallel(); + + void set_loop_to(unsigned int loop_to); + unsigned int loop_to(); + unsigned int *mutable_loop_to(); + + void set_dir(std::string name); + std::string dir(); + std::string *mutable_dir(); + + void set_params(const std::vector &name); + std::vector params(); + std::vector *mutable_params(); + + protected: + std::string name_; + bool is_parallel_; + unsigned int loop_to_; + std::string dir_; + TaskKind kind_ = TaskKind::LUA; + std::vector params_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class TaskIds : public JSONBase { + public: + void set_ids(std::vector ids); + std::vector ids(); + std::vector *mutable_ids(); + + protected: + std::vector ids_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class TaskIndex : public JSONBase { + public: + void set_id(unsigned int id); + unsigned int id(); + unsigned int *mutable_id(); + + protected: + unsigned int id_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class Task : public JSONBase { + public: + void set_id(unsigned int id); + unsigned int id(); + unsigned int *mutable_id(); + + void set_block_id(std::string block_id); + std::string block_id(); + std::string *mutable_block_id(); + + void set_state(TaskState state); + TaskState state(); + TaskState *mutable_state(); + + void set_loopc(unsigned int loopc); + unsigned int loopc(); + unsigned int *mutable_loopc(); + + void set_loopt(unsigned int loopt); + unsigned int loopt(); + unsigned int *mutable_loopt(); + + void set_is_parallel(bool is_parallel); + bool is_parallel(); + bool *mutable_is_parallel(); + + void set_is_simu(bool is_simu); + bool is_simu(); + bool *mutable_is_simu(); + + void set_out(std::string out); + std::string out(); + std::string *mutable_out(); + + void set_started_at(std::string started_at); + std::string started_at(); + std::string *mutable_started_at(); + + void set_ended_at(std::string ended_at); + std::string ended_at(); + std::string *mutable_ended_at(); + + void set_pause_at(std::string pause_at); + std::string pause_at(); + std::string *mutable_pause_at(); + + void set_pre_pause(unsigned int pre_pause); + unsigned int pre_pause(); + unsigned int *mutable_pre_pause(); + + void set_kind(TaskKind kind); + TaskKind kind(); + TaskKind *mutable_kind(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_params(std::vector params); + std::vector params(); + std::vector *mutable_params(); + + protected: + unsigned int id_; + std::string block_id_; + TaskState state_; + unsigned int loopc_; + unsigned int loopt_; + bool is_parallel_; + bool is_simu_; + std::string out_; + std::string started_at_; + std::string ended_at_; + std::string pause_at_; + unsigned int pre_pause_; + TaskKind kind_; + std::string dir_; + std::string name_; + std::vector params_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class PauseRequest : public JSONBase { + public: + void set_id(unsigned int id); + unsigned int id(); + unsigned int *mutable_id(); + + void set_time(unsigned long time); + unsigned long time(); + unsigned long *mutable_time(); + + void set_wait(bool wait); + bool wait(); + bool *mutable_wait(); + + protected: + unsigned int id_; + unsigned long time_; + bool wait_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class Exec : public JSONBase { + public: + void set_id(unsigned int id); + unsigned int id(); + unsigned int *mutable_id(); + + protected: + unsigned int id_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class HookResponse : public JSONBase { + public: + void set_success(unsigned int success); + unsigned int success(); + unsigned int *mutable_success(); + + void set_error(std::string error); + std::string error(); + std::string *mutable_error(); + + protected: + unsigned int success_; + std::string error_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace control +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/db.cc b/sdk/src/protos/db.cc index 91f214d..e026a23 100644 --- a/sdk/src/protos/db.cc +++ b/sdk/src/protos/db.cc @@ -1,459 +1,266 @@ #include "db.hh" -namespace lebai -{ - namespace db - { - void DeleteRequest::set_name(std::string name) - { - name_ = name; - } - std::string DeleteRequest::name() - { - return name_; - } - std::string *DeleteRequest::mutable_name() - { - return &name_; - } +namespace lebai { +namespace db { +void DeleteRequest::set_name(std::string name) { name_ = name; } +std::string DeleteRequest::name() { return name_; } +std::string *DeleteRequest::mutable_name() { return &name_; } - void DeleteRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string DeleteRequest::dir() - { - return dir_; - } - std::string *DeleteRequest::mutable_dir() - { - return &dir_; - } - bool DeleteRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool DeleteRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool DeleteRequest::IsNullJSONData() const - { - return false; - } +void DeleteRequest::set_dir(std::string dir) { dir_ = dir; } +std::string DeleteRequest::dir() { return dir_; } +std::string *DeleteRequest::mutable_dir() { return &dir_; } +bool DeleteRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool DeleteRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool DeleteRequest::IsNullJSONData() const { return false; } - void Dir::set_name(std::string name) - { - name_ = name; - } - std::string Dir::name() - { - return name_; - } - std::string *Dir::mutable_name() - { - return &name_; - } +void Dir::set_name(std::string name) { name_ = name; } +std::string Dir::name() { return name_; } +std::string *Dir::mutable_name() { return &name_; } - void Dir::set_id(unsigned int id) - { - id_ = id; - } - unsigned int Dir::id() - { - return id_; - } - unsigned int *Dir::mutable_id() - { - return &id_; - } +void Dir::set_id(unsigned int id) { id_ = id; } +unsigned int Dir::id() { return id_; } +unsigned int *Dir::mutable_id() { return &id_; } - bool Dir::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("id")) - { - unsigned int id_int = (unsigned int)(obj["id"].GetUint()); - id_ = id_int; - } - return true; - } - bool Dir::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("id"); - writer->Uint(id_); - writer->EndObject(); - return true; - } - bool Dir::IsNullJSONData() const - { - return false; - } - void Dirs::set_dirs(std::vector dirs) - { - dirs_ = dirs; - } - std::vector Dirs::dirs() - { - return dirs_; - } - std::vector *Dirs::mutable_dirs() - { - return &dirs_; - } +bool Dir::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("id")) { + unsigned int id_int = (unsigned int)(obj["id"].GetUint()); + id_ = id_int; + } + return true; +} +bool Dir::Serialize(rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("id"); + writer->Uint(id_); + writer->EndObject(); + return true; +} +bool Dir::IsNullJSONData() const { return false; } +void Dirs::set_dirs(std::vector dirs) { dirs_ = dirs; } +std::vector Dirs::dirs() { return dirs_; } +std::vector *Dirs::mutable_dirs() { return &dirs_; } - bool Dirs::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("dir")) - { - std::vector dirs; - for(auto d = obj["dir"].Begin();d != obj["dir"].End();d++) - { - Dir dir; - dir.FromJSONString(d->GetString()); - dirs.push_back(dir); - } - dirs_ = dirs; - } - return true; - } - bool Dirs::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("dir"); - writer->StartArray(); - for(auto d:dirs_) - { - writer->String(d.ToJSONString().c_str()); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool Dirs::IsNullJSONData() const - { - return false; - } +bool Dirs::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("dir")) { + std::vector dirs; + for (auto d = obj["dir"].Begin(); d != obj["dir"].End(); d++) { + Dir dir; + dir.FromJSONString(d->GetString()); + dirs.push_back(dir); + } + dirs_ = dirs; + } + return true; +} +bool Dirs::Serialize(rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("dir"); + writer->StartArray(); + for (auto d : dirs_) { + writer->String(d.ToJSONString().c_str()); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool Dirs::IsNullJSONData() const { return false; } - void LoadListRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string LoadListRequest::dir() - { - return dir_; - } - std::string *LoadListRequest::mutable_dir() - { - return &dir_; - } - bool LoadListRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool LoadListRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool LoadListRequest::IsNullJSONData() const - { - return false; - } - - void LoadListResponse::set_data(std::vector data) - { - data_ = data; - } - std::vector LoadListResponse::data() - { - return data_; - } - std::vector *LoadListResponse::mutable_data() - { - return &data_; - } +void LoadListRequest::set_dir(std::string dir) { dir_ = dir; } +std::string LoadListRequest::dir() { return dir_; } +std::string *LoadListRequest::mutable_dir() { return &dir_; } +bool LoadListRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool LoadListRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool LoadListRequest::IsNullJSONData() const { return false; } - bool LoadListResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("data")) - { - std::vector data; - for(auto d = obj["data"].Begin();d != obj["data"].End();d++) - { - std::string data_str = (std::string)(d->GetString()); - data.push_back(data_str); - } - data_ = data; - } - return true; - } - bool LoadListResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("data"); - writer->StartArray(); - for(auto d:data_){ - writer->String(d.c_str()); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool LoadListResponse::IsNullJSONData() const - { - return false; - } +void LoadListResponse::set_data(std::vector data) { data_ = data; } +std::vector LoadListResponse::data() { return data_; } +std::vector *LoadListResponse::mutable_data() { return &data_; } - void LoadRequest::set_name(std::string name) - { - name_ = name; - } - std::string LoadRequest::name() - { - return name_; - } - std::string *LoadRequest::mutable_name() - { - return &name_; - } +bool LoadListResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("data")) { + std::vector data; + for (auto d = obj["data"].Begin(); d != obj["data"].End(); d++) { + std::string data_str = (std::string)(d->GetString()); + data.push_back(data_str); + } + data_ = data; + } + return true; +} +bool LoadListResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("data"); + writer->StartArray(); + for (auto d : data_) { + writer->String(d.c_str()); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool LoadListResponse::IsNullJSONData() const { return false; } - void LoadRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string LoadRequest::dir() - { - return dir_; - } - std::string *LoadRequest::mutable_dir() - { - return &dir_; - } +void LoadRequest::set_name(std::string name) { name_ = name; } +std::string LoadRequest::name() { return name_; } +std::string *LoadRequest::mutable_name() { return &name_; } - bool LoadRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool LoadRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool LoadRequest::IsNullJSONData() const - { - return false; - } - - void LoadResponse::set_data(std::string data) - { - data_ = data; - } - std::string LoadResponse::data() - { - return data_; - } - std::string * LoadResponse::mutable_data() - { - return &data_; - } +void LoadRequest::set_dir(std::string dir) { dir_ = dir; } +std::string LoadRequest::dir() { return dir_; } +std::string *LoadRequest::mutable_dir() { return &dir_; } - bool LoadResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("data")) - { - std::string data_str = (std::string)(obj["data"].GetString()); - data_ = data_str; - } - return true; - } - bool LoadResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("data"); - writer->String(data_.c_str()); - writer->EndObject(); - return true; - } - bool LoadResponse::IsNullJSONData() const - { - return false; - } +bool LoadRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool LoadRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool LoadRequest::IsNullJSONData() const { return false; } - void SaveRequest::set_name(std::string name) - { - name_ = name; - } - std::string SaveRequest::name() - { - return name_; - } - std::string *SaveRequest::mutable_name() - { - return &name_; - } +void LoadResponse::set_data(std::string data) { data_ = data; } +std::string LoadResponse::data() { return data_; } +std::string *LoadResponse::mutable_data() { return &data_; } - void SaveRequest::set_data(std::string data) - { - data_ = data; - } - std::string SaveRequest::data() - { - return data_; - } - std::string *SaveRequest::mutable_data() - { - return &data_; - } +bool LoadResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("data")) { + std::string data_str = (std::string)(obj["data"].GetString()); + data_ = data_str; + } + return true; +} +bool LoadResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("data"); + writer->String(data_.c_str()); + writer->EndObject(); + return true; +} +bool LoadResponse::IsNullJSONData() const { return false; } - void SaveRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string SaveRequest::dir() - { - return dir_; - } - std::string *SaveRequest::mutable_dir() - { - return &dir_; - } - - bool SaveRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("data")) - { - std::string data_str = (std::string)(obj["data"].GetString()); - data_ = data_str; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool SaveRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("data"); - writer->String(data_.c_str()); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool SaveRequest::IsNullJSONData() const - { - return false; - } +void SaveRequest::set_name(std::string name) { name_ = name; } +std::string SaveRequest::name() { return name_; } +std::string *SaveRequest::mutable_name() { return &name_; } - void UpdateDirRequest::set_from(std::string from) - { - from_ = from; - } - std::string UpdateDirRequest::from() - { - return from_; - } - std::string *UpdateDirRequest::mutable_from() - { - return &from_; - } +void SaveRequest::set_data(std::string data) { data_ = data; } +std::string SaveRequest::data() { return data_; } +std::string *SaveRequest::mutable_data() { return &data_; } - void UpdateDirRequest::set_to(std::string to) - { - to_ = to; - } - std::string UpdateDirRequest::to() - { - return to_; - } - std::string *UpdateDirRequest::mutable_to() - { - return &to_; - } +void SaveRequest::set_dir(std::string dir) { dir_ = dir; } +std::string SaveRequest::dir() { return dir_; } +std::string *SaveRequest::mutable_dir() { return &dir_; } - bool UpdateDirRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("from")) - { - std::string from_str = (std::string)(obj["from"].GetString()); - from_ = from_str; - } - if(obj.HasMember("to")) - { - std::string to_str = (std::string)(obj["to"].GetString()); - to_ = to_str; - } - return true; - } - bool UpdateDirRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("from"); - writer->String(from_.c_str()); - writer->Key("to"); - writer->String(to_.c_str()); - writer->EndObject(); - return true; - } - bool UpdateDirRequest::IsNullJSONData() const - { - return false; - } - } -} \ No newline at end of file +bool SaveRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("data")) { + std::string data_str = (std::string)(obj["data"].GetString()); + data_ = data_str; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool SaveRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("data"); + writer->String(data_.c_str()); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool SaveRequest::IsNullJSONData() const { return false; } + +void UpdateDirRequest::set_from(std::string from) { from_ = from; } +std::string UpdateDirRequest::from() { return from_; } +std::string *UpdateDirRequest::mutable_from() { return &from_; } + +void UpdateDirRequest::set_to(std::string to) { to_ = to; } +std::string UpdateDirRequest::to() { return to_; } +std::string *UpdateDirRequest::mutable_to() { return &to_; } + +bool UpdateDirRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("from")) { + std::string from_str = (std::string)(obj["from"].GetString()); + from_ = from_str; + } + if (obj.HasMember("to")) { + std::string to_str = (std::string)(obj["to"].GetString()); + to_ = to_str; + } + return true; +} +bool UpdateDirRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("from"); + writer->String(from_.c_str()); + writer->Key("to"); + writer->String(to_.c_str()); + writer->EndObject(); + return true; +} +bool UpdateDirRequest::IsNullJSONData() const { return false; } +} // namespace db +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/db.hh b/sdk/src/protos/db.hh index a89b309..3d74f37 100644 --- a/sdk/src/protos/db.hh +++ b/sdk/src/protos/db.hh @@ -4,182 +4,180 @@ #include #include -namespace lebai -{ - namespace db - { - class DeleteRequest : public JSONBase - { - public: - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - std::string name_; - std::string dir_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class Dir : public JSONBase - { - public: - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_id(unsigned int id); - unsigned int id(); - unsigned int * mutable_id(); - - protected: - std::string name_; - unsigned int id_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class Dirs : public JSONBase - { - public: - void set_dirs(std::vector dirs); - std::vector dirs(); - std::vector * mutable_dirs(); - - protected: - std::vector dirs_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class LoadListRequest : public JSONBase - { - public: - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - std::string dir_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class LoadListResponse : public JSONBase - { - public: - void set_data(std::vector data); - std::vector data(); - std::vector * mutable_data(); - - protected: - std::vector data_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class LoadRequest : public JSONBase - { - public: - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - std::string name_; - std::string dir_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class LoadResponse : public JSONBase - { - public: - void set_data(std::string data); - std::string data(); - std::string * mutable_data(); - - protected: - std::string data_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SaveRequest : public JSONBase - { - public: - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_data(std::string data); - std::string data(); - std::string * mutable_data(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - std::string name_; - std::string data_; - std::string dir_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class UpdateDirRequest : public JSONBase - { - public: - void set_from(std::string from); - std::string from(); - std::string * mutable_from(); - - void set_to(std::string to); - std::string to(); - std::string * mutable_to(); - - protected: - std::string from_; - std::string to_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +namespace lebai { +namespace db { +class DeleteRequest : public JSONBase { + public: + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + std::string name_; + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class Dir : public JSONBase { + public: + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_id(unsigned int id); + unsigned int id(); + unsigned int *mutable_id(); + + protected: + std::string name_; + unsigned int id_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class Dirs : public JSONBase { + public: + void set_dirs(std::vector dirs); + std::vector dirs(); + std::vector *mutable_dirs(); + + protected: + std::vector dirs_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadListRequest : public JSONBase { + public: + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadListResponse : public JSONBase { + public: + void set_data(std::vector data); + std::vector data(); + std::vector *mutable_data(); + + protected: + std::vector data_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadRequest : public JSONBase { + public: + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + std::string name_; + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadResponse : public JSONBase { + public: + void set_data(std::string data); + std::string data(); + std::string *mutable_data(); + + protected: + std::string data_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SaveRequest : public JSONBase { + public: + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_data(std::string data); + std::string data(); + std::string *mutable_data(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + std::string name_; + std::string data_; + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class UpdateDirRequest : public JSONBase { + public: + void set_from(std::string from); + std::string from(); + std::string *mutable_from(); + + void set_to(std::string to); + std::string to(); + std::string *mutable_to(); + + protected: + std::string from_; + std::string to_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace db +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/dynamic.cc b/sdk/src/protos/dynamic.cc index a6275a2..10e6e4b 100644 --- a/sdk/src/protos/dynamic.cc +++ b/sdk/src/protos/dynamic.cc @@ -1,275 +1,159 @@ -#include "dynamic.hh" -#include #include +#include "dynamic.hh" -namespace lebai -{ - namespace dynamic - { - void SetMassRequest::set_mass(double mass) - { - mass_ = mass; - } - double SetMassRequest::mass() const - { - return mass_; - } - double *SetMassRequest::mutable_mass() - { - return &mass_; - } - bool SetMassRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("mass")) - { - double mass = (double)(obj["mass"].GetDouble()); - mass_ = mass; - } - return true; - } - bool SetMassRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("mass"); - writer->Double(mass_); - writer->EndObject(); - return true; - } - bool SetMassRequest::IsNullJSONData() const - { - return false; - } - +namespace lebai { +namespace dynamic { +void SetMassRequest::set_mass(double mass) { mass_ = mass; } +double SetMassRequest::mass() const { return mass_; } +double *SetMassRequest::mutable_mass() { return &mass_; } +bool SetMassRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("mass")) { + double mass = (double)(obj["mass"].GetDouble()); + mass_ = mass; + } + return true; +} +bool SetMassRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("mass"); + writer->Double(mass_); + writer->EndObject(); + return true; +} +bool SetMassRequest::IsNullJSONData() const { return false; } - void SetCogRequest::set_cog(posture::Position cog) - { - cog_ = cog; - } - posture::Position SetCogRequest::cog() const - { - return cog_; - } - posture::Position *SetCogRequest::mutable_cog() - { - return &cog_; - } +void SetCogRequest::set_cog(posture::Position cog) { cog_ = cog; } +posture::Position SetCogRequest::cog() const { return cog_; } +posture::Position *SetCogRequest::mutable_cog() { return &cog_; } - bool SetCogRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("cog")) - { - posture::Position cog; - cog.set_x(obj["cog"].GetObject()["x"].GetDouble()); - cog.set_y(obj["cog"].GetObject()["y"].GetDouble()); - cog.set_z(obj["cog"].GetObject()["z"].GetDouble()); - cog_ = cog; - } - return true; - } - bool SetCogRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("cog"); - cog_.Serialize(writer); - writer->EndObject(); - return true; - } - bool SetCogRequest::IsNullJSONData() const - { - return false; - } - - - void SetPayloadRequest::set_mass(double mass) - { - mass_ = mass; - } - double SetPayloadRequest::mass() const - { - return mass_; - } - double *SetPayloadRequest::mutable_mass() - { - return &mass_; - } +bool SetCogRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("cog")) { + posture::Position cog; + cog.set_x(obj["cog"].GetObject()["x"].GetDouble()); + cog.set_y(obj["cog"].GetObject()["y"].GetDouble()); + cog.set_z(obj["cog"].GetObject()["z"].GetDouble()); + cog_ = cog; + } + return true; +} +bool SetCogRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("cog"); + cog_.Serialize(writer); + writer->EndObject(); + return true; +} +bool SetCogRequest::IsNullJSONData() const { return false; } - void SetPayloadRequest::set_cog(posture::Position cog) - { - cog_ = cog; - } - posture::Position SetPayloadRequest::cog() const - { - return cog_; - } - posture::Position *SetPayloadRequest::mutable_cog() - { - return &cog_; - } +void SetPayloadRequest::set_mass(double mass) { mass_ = mass; } +double SetPayloadRequest::mass() const { return mass_; } +double *SetPayloadRequest::mutable_mass() { return &mass_; } - bool SetPayloadRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("mass")) - { - double mass = (double)(obj["mass"].GetDouble()); - mass_ = mass; - } - if(obj.HasMember("cog")) - { - posture::Position cog; - cog.set_x(obj["cog"].GetObject()["x"].GetDouble()); - cog.set_y(obj["cog"].GetObject()["y"].GetDouble()); - cog.set_z(obj["cog"].GetObject()["z"].GetDouble()); - cog_ = cog; - } - return true; - } - bool SetPayloadRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("mass"); - writer->Double(mass_); - writer->Key("cog"); - cog_.Serialize(writer); - writer->EndObject(); - return true; - } - bool SetPayloadRequest::IsNullJSONData() const - { - return false; - } +void SetPayloadRequest::set_cog(posture::Position cog) { cog_ = cog; } +posture::Position SetPayloadRequest::cog() const { return cog_; } +posture::Position *SetPayloadRequest::mutable_cog() { return &cog_; } +bool SetPayloadRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("mass")) { + double mass = (double)(obj["mass"].GetDouble()); + mass_ = mass; + } + if (obj.HasMember("cog")) { + posture::Position cog; + cog.set_x(obj["cog"].GetObject()["x"].GetDouble()); + cog.set_y(obj["cog"].GetObject()["y"].GetDouble()); + cog.set_z(obj["cog"].GetObject()["z"].GetDouble()); + cog_ = cog; + } + return true; +} +bool SetPayloadRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("mass"); + writer->Double(mass_); + writer->Key("cog"); + cog_.Serialize(writer); + writer->EndObject(); + return true; +} +bool SetPayloadRequest::IsNullJSONData() const { return false; } - void Payload::set_mass(double mass) - { - mass_ = mass; - } - double Payload::mass() const - { - return mass_; - } - double *Payload::mutable_mass() - { - return &mass_; - } +void Payload::set_mass(double mass) { mass_ = mass; } +double Payload::mass() const { return mass_; } +double *Payload::mutable_mass() { return &mass_; } - void Payload::set_cog(posture::Position cog) - { - cog_ = cog; - } - posture::Position Payload::cog() const - { - return cog_; - } - posture::Position *Payload::mutable_cog() - { - return &cog_; - } +void Payload::set_cog(posture::Position cog) { cog_ = cog; } +posture::Position Payload::cog() const { return cog_; } +posture::Position *Payload::mutable_cog() { return &cog_; } - bool Payload::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("mass")) - { - double mass = (double)(obj["mass"].GetDouble()); - mass_ = mass; - } - if(obj.HasMember("cog")) - { - posture::Position cog; - cog.set_x(obj["cog"].GetObject()["x"].GetDouble()); - cog.set_y(obj["cog"].GetObject()["y"].GetDouble()); - cog.set_z(obj["cog"].GetObject()["z"].GetDouble()); - cog_ = cog; - } - return true; - } - bool Payload::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("mass"); - writer->Double(mass_); - writer->Key("cog"); - cog_.Serialize(writer); - writer->EndObject(); - return true; - } - bool Payload::IsNullJSONData() const - { - return false; - } +bool Payload::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("mass")) { + double mass = (double)(obj["mass"].GetDouble()); + mass_ = mass; + } + if (obj.HasMember("cog")) { + posture::Position cog; + cog.set_x(obj["cog"].GetObject()["x"].GetDouble()); + cog.set_y(obj["cog"].GetObject()["y"].GetDouble()); + cog.set_z(obj["cog"].GetObject()["z"].GetDouble()); + cog_ = cog; + } + return true; +} +bool Payload::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("mass"); + writer->Double(mass_); + writer->Key("cog"); + cog_.Serialize(writer); + writer->EndObject(); + return true; +} +bool Payload::IsNullJSONData() const { return false; } - void SavePayloadRequest::set_name(std::string name) - { - name_ = name; - } - std::string SavePayloadRequest::name() const - { - return name_; - } - std::string *SavePayloadRequest::mutable_name() - { - return &name_; - } +void SavePayloadRequest::set_name(std::string name) { name_ = name; } +std::string SavePayloadRequest::name() const { return name_; } +std::string *SavePayloadRequest::mutable_name() { return &name_; } - void SavePayloadRequest::set_data(Payload data) - { - data_ = data; - } - Payload SavePayloadRequest::data() const - { - return data_; - } - Payload *SavePayloadRequest::mutable_data() - { - return &data_; - } +void SavePayloadRequest::set_data(Payload data) { data_ = data; } +Payload SavePayloadRequest::data() const { return data_; } +Payload *SavePayloadRequest::mutable_data() { return &data_; } - void SavePayloadRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string SavePayloadRequest::dir() const - { - return dir_; - } - std::string *SavePayloadRequest::mutable_dir() - { - return &dir_; - } - bool SavePayloadRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("name")) - { - std::string name = (std::string)(obj["name"].GetString()); - name_ = name; - } - if(obj.HasMember("data")) - { - Payload data; - data.FromJSONString(obj["data"].GetString()); - data_ = data; - } - if(obj.HasMember("dir")) - { - std::string dir = (std::string)(obj["dir"].GetString()); - dir_ = dir; - } - return true; - } - bool SavePayloadRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("data"); - writer->String(data_.ToJSONString().c_str()); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool SavePayloadRequest::IsNullJSONData() const - { - return false; - } - } -} \ No newline at end of file +void SavePayloadRequest::set_dir(std::string dir) { dir_ = dir; } +std::string SavePayloadRequest::dir() const { return dir_; } +std::string *SavePayloadRequest::mutable_dir() { return &dir_; } +bool SavePayloadRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + std::string name = (std::string)(obj["name"].GetString()); + name_ = name; + } + if (obj.HasMember("data")) { + Payload data; + data.FromJSONString(obj["data"].GetString()); + data_ = data; + } + if (obj.HasMember("dir")) { + std::string dir = (std::string)(obj["dir"].GetString()); + dir_ = dir; + } + return true; +} +bool SavePayloadRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("data"); + writer->String(data_.ToJSONString().c_str()); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool SavePayloadRequest::IsNullJSONData() const { return false; } +} // namespace dynamic +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/dynamic.hh b/sdk/src/protos/dynamic.hh index 4e8bed7..5d43a7f 100644 --- a/sdk/src/protos/dynamic.hh +++ b/sdk/src/protos/dynamic.hh @@ -6,112 +6,111 @@ #include #include "posture.hh" -namespace lebai -{ - namespace dynamic - { - class SetPayloadRequest : public JSONBase - { - public: - void set_mass(double mass); - double mass() const; - double *mutable_mass(); +namespace lebai { +namespace dynamic { +class SetPayloadRequest : public JSONBase { + public: + void set_mass(double mass); + double mass() const; + double *mutable_mass(); - void set_cog(posture::Position cog); - posture::Position cog() const; - posture::Position * mutable_cog(); + void set_cog(posture::Position cog); + posture::Position cog() const; + posture::Position *mutable_cog(); - protected: - double mass_; - posture::Position cog_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; + protected: + double mass_; + posture::Position cog_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - class SetCogRequest : public JSONBase - { - public: - void set_cog(posture::Position cog); - posture::Position cog() const; - posture::Position * mutable_cog(); +class SetCogRequest : public JSONBase { + public: + void set_cog(posture::Position cog); + posture::Position cog() const; + posture::Position *mutable_cog(); - protected: - posture::Position cog_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; + protected: + posture::Position cog_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - class SetMassRequest : public JSONBase - { - public: - void set_mass(double mass); - double mass() const; - double *mutable_mass(); +class SetMassRequest : public JSONBase { + public: + void set_mass(double mass); + double mass() const; + double *mutable_mass(); - protected: - double mass_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; + protected: + double mass_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - class Payload : public JSONBase - { - public: - void set_mass(double mass); - double mass() const; - double *mutable_mass(); +class Payload : public JSONBase { + public: + void set_mass(double mass); + double mass() const; + double *mutable_mass(); - void set_cog(posture::Position cog); - posture::Position cog() const; - posture::Position * mutable_cog(); + void set_cog(posture::Position cog); + posture::Position cog() const; + posture::Position *mutable_cog(); - protected: - double mass_; - posture::Position cog_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; + protected: + double mass_; + posture::Position cog_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - class SavePayloadRequest : public JSONBase - { - public: - void set_name(std::string name); - std::string name() const; - std::string *mutable_name(); +class SavePayloadRequest : public JSONBase { + public: + void set_name(std::string name); + std::string name() const; + std::string *mutable_name(); - void set_data(Payload data); - Payload data() const; - Payload * mutable_data(); + void set_data(Payload data); + Payload data() const; + Payload *mutable_data(); - void set_dir(std::string dir); - std::string dir() const; - std::string *mutable_dir(); - protected: - std::string name_; - Payload data_; - std::string dir_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file + void set_dir(std::string dir); + std::string dir() const; + std::string *mutable_dir(); + + protected: + std::string name_; + Payload data_; + std::string dir_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace dynamic +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/file.cc b/sdk/src/protos/file.cc index c6ef080..8a11503 100644 --- a/sdk/src/protos/file.cc +++ b/sdk/src/protos/file.cc @@ -1,721 +1,414 @@ #include #include "file.hh" -namespace lebai -{ - namespace file - { - void File::set_is_dir(bool is_dir) - { - is_dir_ = is_dir; - } - bool File::is_dir() - { - return is_dir_; - } - bool * File::mutable_is_dir() - { - return &is_dir_; - } - void File::set_data(std::string data) - { - data_ = data; - } - std::string File::data() - { - return data_; - } - std::string * File::mutable_data() - { - return &data_; - } - bool File::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("is_dir")) - { - bool dir_bool = (unsigned int)(obj["is_dir"].GetBool()); - is_dir_ = dir_bool; - } - if(obj.HasMember("data")) - { - std::string data_str = (std::string)(obj["data"].GetString()); - data_ = data_str; - } - return true; - } - bool File::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("is_dir"); - writer->Bool(is_dir_); - writer->Key("data"); - writer->String(data_.c_str()); - writer->EndObject(); - return true; - } - bool File::IsNullJSONData() const - { - return false; - } +namespace lebai { +namespace file { +void File::set_is_dir(bool is_dir) { is_dir_ = is_dir; } +bool File::is_dir() { return is_dir_; } +bool *File::mutable_is_dir() { return &is_dir_; } +void File::set_data(std::string data) { data_ = data; } +std::string File::data() { return data_; } +std::string *File::mutable_data() { return &data_; } +bool File::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("is_dir")) { + bool dir_bool = (unsigned int)(obj["is_dir"].GetBool()); + is_dir_ = dir_bool; + } + if (obj.HasMember("data")) { + std::string data_str = (std::string)(obj["data"].GetString()); + data_ = data_str; + } + return true; +} +bool File::Serialize(rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("is_dir"); + writer->Bool(is_dir_); + writer->Key("data"); + writer->String(data_.c_str()); + writer->EndObject(); + return true; +} +bool File::IsNullJSONData() const { return false; } - void FileIndex::set_dir(std::string dir) - { - dir_ = dir; - } - std::string FileIndex::dir() - { - return dir_; - } - std::string * FileIndex::mutable_dir() - { - return &dir_; - } - void FileIndex::set_name(std::string name) - { - name_ = name; - } - std::string FileIndex::name() - { - return name_; - } - std::string * FileIndex::mutable_name() - { - return &name_; - } +void FileIndex::set_dir(std::string dir) { dir_ = dir; } +std::string FileIndex::dir() { return dir_; } +std::string *FileIndex::mutable_dir() { return &dir_; } +void FileIndex::set_name(std::string name) { name_ = name; } +std::string FileIndex::name() { return name_; } +std::string *FileIndex::mutable_name() { return &name_; } - bool FileIndex::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - return true; - } - bool FileIndex::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->Key("name"); - writer->String(name_.c_str()); - writer->EndObject(); - return true; - } - bool FileIndex::IsNullJSONData() const - { - return false; - } +bool FileIndex::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + return true; +} +bool FileIndex::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->Key("name"); + writer->String(name_.c_str()); + writer->EndObject(); + return true; +} +bool FileIndex::IsNullJSONData() const { return false; } - void FileName::set_name(std::string name) - { - name_ = name; - } - std::string FileName::name() - { - return name_; - } - std::string * FileName::mutable_name() - { - return &name_; - } - void FileName::set_is_dir(bool is_dir) - { - is_dir_ = is_dir; - } - bool FileName::is_dir() - { - return is_dir_; - } - bool * FileName::mutable_is_dir() - { - return &is_dir_; - } +void FileName::set_name(std::string name) { name_ = name; } +std::string FileName::name() { return name_; } +std::string *FileName::mutable_name() { return &name_; } +void FileName::set_is_dir(bool is_dir) { is_dir_ = is_dir; } +bool FileName::is_dir() { return is_dir_; } +bool *FileName::mutable_is_dir() { return &is_dir_; } - bool FileName::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("is_dir")) - { - bool is_dir_bool = (bool)(obj["is_dir"].GetBool()); - is_dir_ = is_dir_bool; - } - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - return true; - } - bool FileName::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("is_dir"); - writer->Bool(is_dir_); - writer->EndObject(); - return true; - } - bool FileName::IsNullJSONData() const - { - return false; - } +bool FileName::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("is_dir")) { + bool is_dir_bool = (bool)(obj["is_dir"].GetBool()); + is_dir_ = is_dir_bool; + } + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + return true; +} +bool FileName::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("is_dir"); + writer->Bool(is_dir_); + writer->EndObject(); + return true; +} +bool FileName::IsNullJSONData() const { return false; } - void LoadFileListRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string LoadFileListRequest::dir() - { - return dir_; - } - std::string * LoadFileListRequest::mutable_dir() - { - return &dir_; - } - void LoadFileListRequest::set_prefix(std::string prefix) - { - prefix_ = prefix; - } - std::string LoadFileListRequest::prefix() - { - return prefix_; - } - std::string * LoadFileListRequest::mutable_prefix() - { - return &prefix_; - } - void LoadFileListRequest::set_suffix(std::string suffix) - { - suffix_ = suffix; - } - std::string LoadFileListRequest::suffix() - { - return suffix_; - } - std::string * LoadFileListRequest::mutable_suffix() - { - return &suffix_; - } +void LoadFileListRequest::set_dir(std::string dir) { dir_ = dir; } +std::string LoadFileListRequest::dir() { return dir_; } +std::string *LoadFileListRequest::mutable_dir() { return &dir_; } +void LoadFileListRequest::set_prefix(std::string prefix) { prefix_ = prefix; } +std::string LoadFileListRequest::prefix() { return prefix_; } +std::string *LoadFileListRequest::mutable_prefix() { return &prefix_; } +void LoadFileListRequest::set_suffix(std::string suffix) { suffix_ = suffix; } +std::string LoadFileListRequest::suffix() { return suffix_; } +std::string *LoadFileListRequest::mutable_suffix() { return &suffix_; } - bool LoadFileListRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - if(obj.HasMember("prefix")) - { - std::string prefix_str = (std::string)(obj["prefix"].GetString()); - prefix_ = prefix_str; - } - if(obj.HasMember("suffix")) - { - std::string suffix_str = (std::string)(obj["suffix"].GetString()); - suffix_ = suffix_str; - } - return true; - } - bool LoadFileListRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->Key("prefix"); - writer->String(prefix_.c_str()); - writer->Key("suffix"); - writer->String(suffix_.c_str()); - writer->EndObject(); - return true; - } - bool LoadFileListRequest::IsNullJSONData() const - { - return false; - } +bool LoadFileListRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + if (obj.HasMember("prefix")) { + std::string prefix_str = (std::string)(obj["prefix"].GetString()); + prefix_ = prefix_str; + } + if (obj.HasMember("suffix")) { + std::string suffix_str = (std::string)(obj["suffix"].GetString()); + suffix_ = suffix_str; + } + return true; +} +bool LoadFileListRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->Key("prefix"); + writer->String(prefix_.c_str()); + writer->Key("suffix"); + writer->String(suffix_.c_str()); + writer->EndObject(); + return true; +} +bool LoadFileListRequest::IsNullJSONData() const { return false; } - void LoadFileListResponse::set_files(std::vector files) - { - files_ = files; - } - std::vector LoadFileListResponse::files() - { - return files_; - } - std::vector * LoadFileListResponse::mutable_files() - { - return &files_; - } - bool LoadFileListResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("files")) - { - for(auto file = obj["files"].GetArray().Begin();file != obj["files"].GetArray().End();file++) - { - FileName temp; - temp.FromJSONString((std::string)(file->GetString())); - files_.push_back(temp); - } - } - return true; - } - bool LoadFileListResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("files"); - writer->StartArray(); - for(auto file:files_) - { - writer->String(file.ToJSONString().c_str()); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool LoadFileListResponse::IsNullJSONData() const - { - return false; - } +void LoadFileListResponse::set_files(std::vector files) { + files_ = files; +} +std::vector LoadFileListResponse::files() { return files_; } +std::vector *LoadFileListResponse::mutable_files() { return &files_; } +bool LoadFileListResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("files")) { + for (auto file = obj["files"].GetArray().Begin(); + file != obj["files"].GetArray().End(); file++) { + FileName temp; + temp.FromJSONString((std::string)(file->GetString())); + files_.push_back(temp); + } + } + return true; +} +bool LoadFileListResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("files"); + writer->StartArray(); + for (auto file : files_) { + writer->String(file.ToJSONString().c_str()); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool LoadFileListResponse::IsNullJSONData() const { return false; } + +void SaveFileRequest::set_dir(std::string dir) { dir_ = dir; } +std::string SaveFileRequest::dir() { return dir_; } +std::string *SaveFileRequest::mutable_dir() { return &dir_; } +void SaveFileRequest::set_name(std::string name) { name_ = name; } +std::string SaveFileRequest::name() { return name_; } +std::string *SaveFileRequest::mutable_name() { return &name_; } +void SaveFileRequest::set_file(File file) { file_ = file; } +File SaveFileRequest::file() { return file_; } +File *SaveFileRequest::mutable_file() { return &file_; } - void SaveFileRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string SaveFileRequest::dir() - { - return dir_; - } - std::string * SaveFileRequest::mutable_dir() - { - return &dir_; - } - void SaveFileRequest::set_name(std::string name) - { - name_ = name; - } - std::string SaveFileRequest::name() - { - return name_; - } - std::string * SaveFileRequest::mutable_name() - { - return &name_; - } - void SaveFileRequest::set_file(File file) - { - file_ = file; - } - File SaveFileRequest::file() - { - return file_; - } - File * SaveFileRequest::mutable_file() - { - return &file_; - } +bool SaveFileRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + if (obj.HasMember("name")) { + std::string name_str = (std::string)(obj["name"].GetString()); + name_ = name_str; + } + if (obj.HasMember("file")) { + File temp; + temp.FromJSONString((std::string)(obj["name"].GetString())); + file_ = temp; + } + return true; +} +bool SaveFileRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->Key("name"); + writer->String(name_.c_str()); + writer->Key("file"); + writer->String(file_.ToJSONString().c_str()); + writer->EndObject(); + return true; +} +bool SaveFileRequest::IsNullJSONData() const { return false; } - bool SaveFileRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - if(obj.HasMember("name")) - { - std::string name_str = (std::string)(obj["name"].GetString()); - name_ = name_str; - } - if(obj.HasMember("file")) - { - File temp; - temp.FromJSONString((std::string)(obj["name"].GetString())); - file_ = temp; - } - return true; - } - bool SaveFileRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->Key("name"); - writer->String(name_.c_str()); - writer->Key("file"); - writer->String(file_.ToJSONString().c_str()); - writer->EndObject(); - return true; - } - bool SaveFileRequest::IsNullJSONData() const - { - return false; - } +void RenameFileRequest::set_from(FileIndex from) { from_ = from; } +FileIndex RenameFileRequest::from() { return from_; } +FileIndex *RenameFileRequest::mutable_from() { return &from_; } +void RenameFileRequest::set_to(FileIndex to) { to_ = to; } +FileIndex RenameFileRequest::to() { return to_; } +FileIndex *RenameFileRequest::mutable_to() { return &to_; } +bool RenameFileRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("from")) { + FileIndex from_str; + from_str.FromJSONString((std::string)(obj["from"].GetString())); + from_ = from_str; + } + if (obj.HasMember("to")) { + FileIndex to_str; + to_str.FromJSONString((std::string)(obj["to"].GetString())); + to_ = to_str; + } + return true; +} +bool RenameFileRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("from"); + writer->String(from_.ToJSONString().c_str()); + writer->Key("to"); + writer->String(to_.ToJSONString().c_str()); + writer->EndObject(); + return true; +} +bool RenameFileRequest::IsNullJSONData() const { return false; } - void RenameFileRequest::set_from(FileIndex from) - { - from_ = from; - } - FileIndex RenameFileRequest::from() - { - return from_; - } - FileIndex * RenameFileRequest::mutable_from() - { - return &from_; - } - void RenameFileRequest::set_to(FileIndex to) - { - to_ = to; - } - FileIndex RenameFileRequest::to() - { - return to_; - } - FileIndex * RenameFileRequest::mutable_to() - { - return &to_; - } - bool RenameFileRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("from")) - { - FileIndex from_str; - from_str.FromJSONString((std::string)(obj["from"].GetString())); - from_ = from_str; - } - if(obj.HasMember("to")) - { - FileIndex to_str; - to_str.FromJSONString((std::string)(obj["to"].GetString())); - to_ = to_str; - } - return true; - } - bool RenameFileRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("from"); - writer->String(from_.ToJSONString().c_str()); - writer->Key("to"); - writer->String(to_.ToJSONString().c_str()); - writer->EndObject(); - return true; - } - bool RenameFileRequest::IsNullJSONData() const - { - return false; - } +void ZipRequest::set_zip(file::FileIndex zip) { zip_ = zip; } +file::FileIndex ZipRequest::zip() { return zip_; } +file::FileIndex *ZipRequest::mutable_zip() { return &zip_; } - void ZipRequest::set_zip(file::FileIndex zip) - { - zip_ = zip; - } - file::FileIndex ZipRequest::zip() - { - return zip_; - } - file::FileIndex * ZipRequest::mutable_zip() - { - return &zip_; - } +void ZipRequest::set_files(std::vector files) { files_ = files; } +std::vector ZipRequest::files() { return files_; } +std::vector *ZipRequest::mutable_files() { return &files_; } - void ZipRequest::set_files(std::vector files) - { - files_ = files; - } - std::vector ZipRequest::files() - { - return files_; - } - std::vector * ZipRequest::mutable_files() - { - return &files_; - } +void ZipRequest::set_dir(std::string dir) { dir_ = dir; } +std::string ZipRequest::dir() { return dir_; } +std::string *ZipRequest::mutable_dir() { return &dir_; } +bool ZipRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("zip")) { + FileIndex zip_str; + zip_str.FromJSONString((std::string)(obj["zip"].GetString())); + zip_ = zip_str; + } + if (obj.HasMember("files")) { + std::vector files; + for (auto i = obj["files"].GetArray().Begin(); + i != obj["files"].GetArray().End(); i++) { + files.push_back(i->GetString()); + } + files_ = files; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool ZipRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("zip"); + writer->String(zip_.ToJSONString().c_str()); + writer->Key("files"); + writer->StartArray(); + for (auto f : files_) { + writer->String(f.c_str()); + } + writer->EndArray(); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool ZipRequest::IsNullJSONData() const { return false; } - void ZipRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string ZipRequest::dir() - { - return dir_; - } - std::string * ZipRequest::mutable_dir() - { - return &dir_; - } - bool ZipRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("zip")) - { - FileIndex zip_str; - zip_str.FromJSONString((std::string)(obj["zip"].GetString())); - zip_ = zip_str; - } - if(obj.HasMember("files")) - { - std::vector files; - for(auto i = obj["files"].GetArray().Begin();i != obj["files"].GetArray().End();i++) - { - files.push_back(i->GetString()); - } - files_ = files; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool ZipRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("zip"); - writer->String(zip_.ToJSONString().c_str()); - writer->Key("files"); - writer->StartArray(); - for(auto f:files_) - { - writer->String(f.c_str()); - } - writer->EndArray(); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool ZipRequest::IsNullJSONData() const - { - return false; - } +void UnzipRequest::set_zip(file::FileIndex zip) { zip_ = zip; } +file::FileIndex UnzipRequest::zip() { return zip_; } +file::FileIndex *UnzipRequest::mutable_zip() { return &zip_; } - void UnzipRequest::set_zip(file::FileIndex zip) - { - zip_ = zip; - } - file::FileIndex UnzipRequest::zip() - { - return zip_; - } - file::FileIndex * UnzipRequest::mutable_zip() - { - return &zip_; - } +void UnzipRequest::set_files(std::vector files) { files_ = files; } +std::vector UnzipRequest::files() { return files_; } +std::vector *UnzipRequest::mutable_files() { return &files_; } + +void UnzipRequest::set_dir(std::string dir) { dir_ = dir; } +std::string UnzipRequest::dir() { return dir_; } +std::string *UnzipRequest::mutable_dir() { return &dir_; } +bool UnzipRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("zip")) { + FileIndex zip_str; + zip_str.FromJSONString((std::string)(obj["zip"].GetString())); + zip_ = zip_str; + } + if (obj.HasMember("files")) { + std::vector files; + for (auto i = obj["files"].GetArray().Begin(); + i != obj["files"].GetArray().End(); i++) { + files.push_back(i->GetString()); + } + files_ = files; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + return true; +} +bool UnzipRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("zip"); + writer->String(zip_.ToJSONString().c_str()); + writer->Key("files"); + writer->StartArray(); + for (auto f : files_) { + writer->String(f.c_str()); + } + writer->EndArray(); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->EndObject(); + return true; +} +bool UnzipRequest::IsNullJSONData() const { return false; } - void UnzipRequest::set_files(std::vector files) - { - files_ = files; - } - std::vector UnzipRequest::files() - { - return files_; - } - std::vector * UnzipRequest::mutable_files() - { - return &files_; - } +void LoadZipListRequest::set_zip(FileIndex zip) { zip_ = zip; } +FileIndex LoadZipListRequest::zip() { return zip_; } +FileIndex *LoadZipListRequest::mutable_zip() { return &zip_; } - void UnzipRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string UnzipRequest::dir() - { - return dir_; - } - std::string * UnzipRequest::mutable_dir() - { - return &dir_; - } - bool UnzipRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("zip")) - { - FileIndex zip_str; - zip_str.FromJSONString((std::string)(obj["zip"].GetString())); - zip_ = zip_str; - } - if(obj.HasMember("files")) - { - std::vector files; - for(auto i = obj["files"].GetArray().Begin();i != obj["files"].GetArray().End();i++) - { - files.push_back(i->GetString()); - } - files_ = files; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - return true; - } - bool UnzipRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("zip"); - writer->String(zip_.ToJSONString().c_str()); - writer->Key("files"); - writer->StartArray(); - for(auto f:files_) - { - writer->String(f.c_str()); - } - writer->EndArray(); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->EndObject(); - return true; - } - bool UnzipRequest::IsNullJSONData() const - { - return false; - } +void LoadZipListRequest::set_dir(std::string dir) { dir_ = dir; } +std::string LoadZipListRequest::dir() { return dir_; } +std::string *LoadZipListRequest::mutable_dir() { return &dir_; } - void LoadZipListRequest::set_zip(FileIndex zip) - { - zip_ = zip; - } - FileIndex LoadZipListRequest::zip() - { - return zip_; - } - FileIndex * LoadZipListRequest::mutable_zip() - { - return &zip_; - } +void LoadZipListRequest::set_prefix(std::string prefix) { prefix_ = prefix; } +std::string LoadZipListRequest::prefix() { return prefix_; } +std::string *LoadZipListRequest::mutable_prefix() { return &prefix_; } - void LoadZipListRequest::set_dir(std::string dir) - { - dir_ = dir; - } - std::string LoadZipListRequest::dir() - { - return dir_; - } - std::string *LoadZipListRequest::mutable_dir() - { - return &dir_; - } +void LoadZipListRequest::set_suffix(std::string suffix) { suffix_ = suffix; } +std::string LoadZipListRequest::suffix() { return suffix_; } +std::string *LoadZipListRequest::mutable_suffix() { return &suffix_; } - void LoadZipListRequest::set_prefix(std::string prefix) - { - prefix_ = prefix; - } - std::string LoadZipListRequest::prefix() - { - return prefix_; - } - std::string *LoadZipListRequest::mutable_prefix() - { - return &prefix_; - } +bool LoadZipListRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("zip")) { + FileIndex zip_str; + zip_str.FromJSONString((std::string)(obj["zip"].GetString())); + zip_ = zip_str; + } + if (obj.HasMember("dir")) { + std::string dir_str = (std::string)(obj["dir"].GetString()); + dir_ = dir_str; + } + if (obj.HasMember("prefix")) { + std::string prefix_str = (std::string)(obj["prefix"].GetString()); + prefix_ = prefix_str; + } + if (obj.HasMember("suffix")) { + std::string suffix_str = (std::string)(obj["suffix"].GetString()); + suffix_ = suffix_str; + } + return true; +} +bool LoadZipListRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("zip"); + writer->String(zip_.ToJSONString().c_str()); + writer->Key("dir"); + writer->String(dir_.c_str()); + writer->Key("prefix"); + writer->String(prefix_.c_str()); + writer->Key("suffix"); + writer->String(suffix_.c_str()); + writer->EndObject(); + return true; +} +bool LoadZipListRequest::IsNullJSONData() const { return false; } - void LoadZipListRequest::set_suffix(std::string suffix) - { - suffix_ = suffix; - } - std::string LoadZipListRequest::suffix() - { - return suffix_; - } - std::string *LoadZipListRequest::mutable_suffix() - { - return &suffix_; - } - - bool LoadZipListRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("zip")) - { - FileIndex zip_str; - zip_str.FromJSONString((std::string)(obj["zip"].GetString())); - zip_ = zip_str; - } - if(obj.HasMember("dir")) - { - std::string dir_str = (std::string)(obj["dir"].GetString()); - dir_ = dir_str; - } - if(obj.HasMember("prefix")) - { - std::string prefix_str = (std::string)(obj["prefix"].GetString()); - prefix_ = prefix_str; - } - if(obj.HasMember("suffix")) - { - std::string suffix_str = (std::string)(obj["suffix"].GetString()); - suffix_ = suffix_str; - } - return true; - } - bool LoadZipListRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("zip"); - writer->String(zip_.ToJSONString().c_str()); - writer->Key("dir"); - writer->String(dir_.c_str()); - writer->Key("prefix"); - writer->String(prefix_.c_str()); - writer->Key("suffix"); - writer->String(suffix_.c_str()); - writer->EndObject(); - return true; - } - bool LoadZipListRequest::IsNullJSONData() const - { - return false; - } - - void LoadZipListResponse::set_files(std::vector files) - { - files_ = files; - } - std::vector LoadZipListResponse::files() - { - return files_; - } - std::vector * LoadZipListResponse::mutable_files() - { - return &files_; - } - bool LoadZipListResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("files")) - { - for(auto file = obj["files"].GetArray().Begin();file != obj["files"].GetArray().End();file++) - { - FileName temp; - temp.FromJSONString((std::string)(file->GetString())); - files_.push_back(temp); - } - } - return true; - } - bool LoadZipListResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("files"); - writer->StartArray(); - for(auto file:files_) - { - writer->String(file.ToJSONString().c_str()); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool LoadZipListResponse::IsNullJSONData() const - { - return false; - } +void LoadZipListResponse::set_files(std::vector files) { + files_ = files; +} +std::vector LoadZipListResponse::files() { return files_; } +std::vector *LoadZipListResponse::mutable_files() { return &files_; } +bool LoadZipListResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("files")) { + for (auto file = obj["files"].GetArray().Begin(); + file != obj["files"].GetArray().End(); file++) { + FileName temp; + temp.FromJSONString((std::string)(file->GetString())); + files_.push_back(temp); } -} \ No newline at end of file + } + return true; +} +bool LoadZipListResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("files"); + writer->StartArray(); + for (auto file : files_) { + writer->String(file.ToJSONString().c_str()); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool LoadZipListResponse::IsNullJSONData() const { return false; } +} // namespace file +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/file.hh b/sdk/src/protos/file.hh index be95f02..1301660 100644 --- a/sdk/src/protos/file.hh +++ b/sdk/src/protos/file.hh @@ -4,250 +4,257 @@ #include #include -namespace lebai -{ - namespace file - { - class File : public JSONBase - { - public: - void set_is_dir(bool is_dir); - bool is_dir(); - bool * mutable_is_dir(); - - void set_data(std::string data); - std::string data(); - std::string * mutable_data(); - - protected: - bool is_dir_; - std::string data_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class FileIndex : public JSONBase - { - public: - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - protected: - std::string dir_; - std::string name_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class FileName : public JSONBase - { - public: - void set_is_dir(bool is_dir); - bool is_dir(); - bool * mutable_is_dir(); - - void set_name(std::string data); - std::string name(); - std::string * mutable_name(); - - protected: - bool is_dir_; - std::string name_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - - class LoadFileListRequest : public JSONBase - { - public: - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - void set_prefix(std::string prefix); - std::string prefix(); - std::string * mutable_prefix(); - - void set_suffix(std::string suffix); - std::string suffix(); - std::string * mutable_suffix(); - - protected: - std::string dir_; - std::string prefix_; - std::string suffix_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class LoadFileListResponse : public JSONBase - { - public: - void set_files(std::vector dir); - std::vector files(); - std::vector * mutable_files(); - - protected: - std::vector files_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SaveFileRequest : public JSONBase - { - public: - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - void set_name(std::string name); - std::string name(); - std::string * mutable_name(); - - void set_file(File file); - File file(); - File * mutable_file(); - - protected: - std::string dir_; - std::string name_; - File file_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class RenameFileRequest : public JSONBase - { - public: - void set_from(FileIndex from); - FileIndex from(); - FileIndex * mutable_from(); - - void set_to(FileIndex to); - FileIndex to(); - FileIndex * mutable_to(); - protected: - FileIndex from_; - FileIndex to_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class ZipRequest : public JSONBase - { - public: - void set_zip(FileIndex zip); - FileIndex zip(); - FileIndex * mutable_zip(); - - void set_files(std::vector files); - std::vector files(); - std::vector * mutable_files(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - FileIndex zip_; - std::vector files_; - std::string dir_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class UnzipRequest : public JSONBase - { - public: - void set_zip(FileIndex zip); - FileIndex zip(); - FileIndex * mutable_zip(); - - void set_files(std::vector files); - std::vector files(); - std::vector * mutable_files(); - - void set_dir(std::string dir); - std::string dir(); - std::string * mutable_dir(); - - protected: - FileIndex zip_; - std::vector files_; - std::string dir_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class LoadZipListRequest : public JSONBase - { - public: - void set_zip(FileIndex zip); - FileIndex zip(); - FileIndex * mutable_zip(); - - void set_dir(std::string dir); - std::string dir(); - std::string *mutable_dir(); - - void set_prefix(std::string prefix); - std::string prefix(); - std::string *mutable_prefix(); - - void set_suffix(std::string suffix); - std::string suffix(); - std::string *mutable_suffix(); - - protected: - FileIndex zip_; - std::string dir_; - std::string prefix_; - std::string suffix_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class LoadZipListResponse : public JSONBase - { - public: - void set_files(std::vector dir); - std::vector files(); - std::vector * mutable_files(); - - protected: - std::vector files_; - - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +namespace lebai { +namespace file { +class File : public JSONBase { + public: + void set_is_dir(bool is_dir); + bool is_dir(); + bool *mutable_is_dir(); + + void set_data(std::string data); + std::string data(); + std::string *mutable_data(); + + protected: + bool is_dir_; + std::string data_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class FileIndex : public JSONBase { + public: + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + protected: + std::string dir_; + std::string name_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class FileName : public JSONBase { + public: + void set_is_dir(bool is_dir); + bool is_dir(); + bool *mutable_is_dir(); + + void set_name(std::string data); + std::string name(); + std::string *mutable_name(); + + protected: + bool is_dir_; + std::string name_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadFileListRequest : public JSONBase { + public: + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + void set_prefix(std::string prefix); + std::string prefix(); + std::string *mutable_prefix(); + + void set_suffix(std::string suffix); + std::string suffix(); + std::string *mutable_suffix(); + + protected: + std::string dir_; + std::string prefix_; + std::string suffix_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadFileListResponse : public JSONBase { + public: + void set_files(std::vector dir); + std::vector files(); + std::vector *mutable_files(); + + protected: + std::vector files_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SaveFileRequest : public JSONBase { + public: + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + void set_name(std::string name); + std::string name(); + std::string *mutable_name(); + + void set_file(File file); + File file(); + File *mutable_file(); + + protected: + std::string dir_; + std::string name_; + File file_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class RenameFileRequest : public JSONBase { + public: + void set_from(FileIndex from); + FileIndex from(); + FileIndex *mutable_from(); + + void set_to(FileIndex to); + FileIndex to(); + FileIndex *mutable_to(); + + protected: + FileIndex from_; + FileIndex to_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class ZipRequest : public JSONBase { + public: + void set_zip(FileIndex zip); + FileIndex zip(); + FileIndex *mutable_zip(); + + void set_files(std::vector files); + std::vector files(); + std::vector *mutable_files(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + FileIndex zip_; + std::vector files_; + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class UnzipRequest : public JSONBase { + public: + void set_zip(FileIndex zip); + FileIndex zip(); + FileIndex *mutable_zip(); + + void set_files(std::vector files); + std::vector files(); + std::vector *mutable_files(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + protected: + FileIndex zip_; + std::vector files_; + std::string dir_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadZipListRequest : public JSONBase { + public: + void set_zip(FileIndex zip); + FileIndex zip(); + FileIndex *mutable_zip(); + + void set_dir(std::string dir); + std::string dir(); + std::string *mutable_dir(); + + void set_prefix(std::string prefix); + std::string prefix(); + std::string *mutable_prefix(); + + void set_suffix(std::string suffix); + std::string suffix(); + std::string *mutable_suffix(); + + protected: + FileIndex zip_; + std::string dir_; + std::string prefix_; + std::string suffix_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class LoadZipListResponse : public JSONBase { + public: + void set_files(std::vector dir); + std::vector files(); + std::vector *mutable_files(); + + protected: + std::vector files_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace file +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/io.cc b/sdk/src/protos/io.cc index 8419da4..1115058 100644 --- a/sdk/src/protos/io.cc +++ b/sdk/src/protos/io.cc @@ -1,1285 +1,743 @@ #include #include "io.hh" +namespace lebai { +namespace io { -namespace lebai -{ - namespace io - { - - void GetDioPinRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice GetDioPinRequest::device() const - { - return device_; - } - IoDevice * GetDioPinRequest::mutable_device() - { - return &device_; - } - void GetDioPinRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int GetDioPinRequest::pin() const - { - return pin_; - } - unsigned int * GetDioPinRequest::mutable_pin() - { - return &pin_; - } - - // Deserialize - bool GetDioPinRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - return true; - } - // Serialize - bool GetDioPinRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Int(pin_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool GetDioPinRequest::IsNullJSONData() const - { - return false; - } +void GetDioPinRequest::set_device(IoDevice device) { device_ = device; } +IoDevice GetDioPinRequest::device() const { return device_; } +IoDevice *GetDioPinRequest::mutable_device() { return &device_; } +void GetDioPinRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int GetDioPinRequest::pin() const { return pin_; } +unsigned int *GetDioPinRequest::mutable_pin() { return &pin_; } - void GetDioPinResponse::set_value(unsigned int value) - { - value_ = value; - } - unsigned int GetDioPinResponse::value() const - { - return value_; - } - unsigned int * GetDioPinResponse::mutable_value() - { - return &value_; - } - // Deserialize - bool GetDioPinResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("value")) - { - value_ = obj["value"].GetUint(); - } - return true; - } - // Serialize - bool GetDioPinResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("value"); - writer->Int(value_); - writer->EndObject(); - return true; +// Deserialize +bool GetDioPinRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } - // IsNullJSONData - bool GetDioPinResponse::IsNullJSONData() const - { - return false; - } - + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + return true; +} +// Serialize +bool GetDioPinRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Int(pin_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetDioPinRequest::IsNullJSONData() const { return false; } - void SetDoPinRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice SetDoPinRequest::device() const - { - return device_; - } - IoDevice * SetDoPinRequest::mutable_device() - { - return &device_; - } - void SetDoPinRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int SetDoPinRequest::pin() const - { - return pin_; - } - unsigned int * SetDoPinRequest::mutable_pin() - { - return &pin_; - } - void SetDoPinRequest::set_value(unsigned int value) - { - value_ = value; - } - unsigned int SetDoPinRequest::value() const - { - return value_; - } - unsigned int * SetDoPinRequest::mutable_value() - { - return &value_; - } - // Deserialize - bool SetDoPinRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("value")) - { - value_ = obj["value"].GetUint(); - } - return true; - } - // Serialize - bool SetDoPinRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Int(pin_); - writer->Key("value"); - writer->Int(value_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool SetDoPinRequest::IsNullJSONData() const - { - return false; - } +void GetDioPinResponse::set_value(unsigned int value) { value_ = value; } +unsigned int GetDioPinResponse::value() const { return value_; } +unsigned int *GetDioPinResponse::mutable_value() { return &value_; } +// Deserialize +bool GetDioPinResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("value")) { + value_ = obj["value"].GetUint(); + } + return true; +} +// Serialize +bool GetDioPinResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("value"); + writer->Int(value_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetDioPinResponse::IsNullJSONData() const { return false; } - void GetAioPinRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice GetAioPinRequest::device() const - { - return device_; - } - IoDevice * GetAioPinRequest::mutable_device() - { - return &device_; - } - void GetAioPinRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int GetAioPinRequest::pin() const - { - return pin_; - } - unsigned int * GetAioPinRequest::mutable_pin() - { - return &pin_; - } - // Deserialize - bool GetAioPinRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - return true; - } - // Serialize - bool GetAioPinRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Int(pin_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool GetAioPinRequest::IsNullJSONData() const - { - return false; +void SetDoPinRequest::set_device(IoDevice device) { device_ = device; } +IoDevice SetDoPinRequest::device() const { return device_; } +IoDevice *SetDoPinRequest::mutable_device() { return &device_; } +void SetDoPinRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int SetDoPinRequest::pin() const { return pin_; } +unsigned int *SetDoPinRequest::mutable_pin() { return &pin_; } +void SetDoPinRequest::set_value(unsigned int value) { value_ = value; } +unsigned int SetDoPinRequest::value() const { return value_; } +unsigned int *SetDoPinRequest::mutable_value() { return &value_; } +// Deserialize +bool SetDoPinRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("value")) { + value_ = obj["value"].GetUint(); + } + return true; +} +// Serialize +bool SetDoPinRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Int(pin_); + writer->Key("value"); + writer->Int(value_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool SetDoPinRequest::IsNullJSONData() const { return false; } - void GetAioPinResponse::set_value(double value) - { - value_ = value; - } - double GetAioPinResponse::value() const - { - return value_; - } - double * GetAioPinResponse::mutable_value() - { - return &value_; - } - // Deserialize - bool GetAioPinResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("value")) - { - value_ = obj["value"].GetDouble(); - } - return true; - } - // Serialize - bool GetAioPinResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("value"); - writer->Double(value_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool GetAioPinResponse::IsNullJSONData() const - { - return false; +void GetAioPinRequest::set_device(IoDevice device) { device_ = device; } +IoDevice GetAioPinRequest::device() const { return device_; } +IoDevice *GetAioPinRequest::mutable_device() { return &device_; } +void GetAioPinRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int GetAioPinRequest::pin() const { return pin_; } +unsigned int *GetAioPinRequest::mutable_pin() { return &pin_; } +// Deserialize +bool GetAioPinRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + return true; +} +// Serialize +bool GetAioPinRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Int(pin_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetAioPinRequest::IsNullJSONData() const { return false; } +void GetAioPinResponse::set_value(double value) { value_ = value; } +double GetAioPinResponse::value() const { return value_; } +double *GetAioPinResponse::mutable_value() { return &value_; } +// Deserialize +bool GetAioPinResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("value")) { + value_ = obj["value"].GetDouble(); + } + return true; +} +// Serialize +bool GetAioPinResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("value"); + writer->Double(value_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetAioPinResponse::IsNullJSONData() const { return false; } - void SetAoPinRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice SetAoPinRequest::device() const - { - return device_; - } - IoDevice * SetAoPinRequest::mutable_device() - { - return &device_; - } - void SetAoPinRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int SetAoPinRequest::pin() const - { - return pin_; - } - unsigned int * SetAoPinRequest::mutable_pin() - { - return &pin_; - } - void SetAoPinRequest::set_value(double value) - { - value_ = value; - } - double SetAoPinRequest::value() const - { - return value_; - } - double * SetAoPinRequest::mutable_value() - { - return &value_; - } - // Deserialize - bool SetAoPinRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("value")) - { - value_ = obj["value"].GetDouble(); - } - return true; - } - // Serialize - bool SetAoPinRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Int(pin_); - writer->Key("value"); - writer->Double(value_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool SetAoPinRequest::IsNullJSONData() const - { - return false; +void SetAoPinRequest::set_device(IoDevice device) { device_ = device; } +IoDevice SetAoPinRequest::device() const { return device_; } +IoDevice *SetAoPinRequest::mutable_device() { return &device_; } +void SetAoPinRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int SetAoPinRequest::pin() const { return pin_; } +unsigned int *SetAoPinRequest::mutable_pin() { return &pin_; } +void SetAoPinRequest::set_value(double value) { value_ = value; } +double SetAoPinRequest::value() const { return value_; } +double *SetAoPinRequest::mutable_value() { return &value_; } +// Deserialize +bool SetAoPinRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("value")) { + value_ = obj["value"].GetDouble(); + } + return true; +} +// Serialize +bool SetAoPinRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Int(pin_); + writer->Key("value"); + writer->Double(value_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool SetAoPinRequest::IsNullJSONData() const { return false; } - void GetDioPinsRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice GetDioPinsRequest::device() const - { - return device_; - } - IoDevice * GetDioPinsRequest::mutable_device() - { - return &device_; - } - void GetDioPinsRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int GetDioPinsRequest::pin() const - { - return pin_; - } - unsigned int * GetDioPinsRequest::mutable_pin() - { - return &pin_; - } +void GetDioPinsRequest::set_device(IoDevice device) { device_ = device; } +IoDevice GetDioPinsRequest::device() const { return device_; } +IoDevice *GetDioPinsRequest::mutable_device() { return &device_; } +void GetDioPinsRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int GetDioPinsRequest::pin() const { return pin_; } +unsigned int *GetDioPinsRequest::mutable_pin() { return &pin_; } - void GetDioPinsRequest::set_count(unsigned int count) - { - count_ = count; - } - unsigned int GetDioPinsRequest::count() const - { - return count_; - } - unsigned int * GetDioPinsRequest::mutable_count() - { - return &count_; - } - // Deserialize - bool GetDioPinsRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("count")) - { - count_ = obj["count"].GetUint(); - } - return true; - } - // Serialize - bool GetDioPinsRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Uint(pin_); - writer->Key("count"); - writer->Uint(count_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool GetDioPinsRequest::IsNullJSONData() const - { - return false; - } - void GetDioPinsResponse::set_values(std::vector values) - { - values_ = values; - } - std::vector GetDioPinsResponse::values() const - { - return values_; - } - std::vector * GetDioPinsResponse::mutable_values() - { - return &values_; - } - // Deserialize - bool GetDioPinsResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back(i->GetUint()); - } - values_ = values; - } - return true; - } - // Serialize - bool GetDioPinsResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("value"); - writer->StartArray(); - for(auto i:values_) - { - writer->Uint(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool GetDioPinsResponse::IsNullJSONData() const - { - return false; +void GetDioPinsRequest::set_count(unsigned int count) { count_ = count; } +unsigned int GetDioPinsRequest::count() const { return count_; } +unsigned int *GetDioPinsRequest::mutable_count() { return &count_; } +// Deserialize +bool GetDioPinsRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("count")) { + count_ = obj["count"].GetUint(); + } + return true; +} +// Serialize +bool GetDioPinsRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Uint(pin_); + writer->Key("count"); + writer->Uint(count_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetDioPinsRequest::IsNullJSONData() const { return false; } +void GetDioPinsResponse::set_values(std::vector values) { + values_ = values; +} +std::vector GetDioPinsResponse::values() const { return values_; } +std::vector *GetDioPinsResponse::mutable_values() { + return &values_; +} +// Deserialize +bool GetDioPinsResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back(i->GetUint()); + } + values_ = values; + } + return true; +} +// Serialize +bool GetDioPinsResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("value"); + writer->StartArray(); + for (auto i : values_) { + writer->Uint(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetDioPinsResponse::IsNullJSONData() const { return false; } - void SetDoPinsRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice SetDoPinsRequest::device() const - { - return device_; - } - IoDevice * SetDoPinsRequest::mutable_device() - { - return &device_; - } - void SetDoPinsRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int SetDoPinsRequest::pin() const - { - return pin_; - } - unsigned int * SetDoPinsRequest::mutable_pin() - { - return &pin_; - } - void SetDoPinsRequest::set_values(std::vector values) - { - values_ = values; - } - std::vector SetDoPinsRequest::values() const - { - return values_; - } - std::vector * SetDoPinsRequest::mutable_values() - { - return &values_; - } - // Deserialize - bool SetDoPinsRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back(i->GetUint()); - } - values_ = values; - } - return true; - } - // Serialize - bool SetDoPinsRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Int(pin_); - writer->Key("value"); - writer->StartArray(); - for(auto i:values_) - { - writer->Uint(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool SetDoPinsRequest::IsNullJSONData() const - { - return false; - } - void GetAioPinsRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice GetAioPinsRequest::device() const - { - return device_; - } - IoDevice * GetAioPinsRequest::mutable_device() - { - return &device_; - } - void GetAioPinsRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int GetAioPinsRequest::pin() const - { - return pin_; - } - unsigned int * GetAioPinsRequest::mutable_pin() - { - return &pin_; - } - void GetAioPinsRequest::set_count(unsigned int count) - { - count_ = count; - } - unsigned int GetAioPinsRequest::count() const - { - return count_; - } - unsigned int * GetAioPinsRequest::mutable_count() - { - return &count_; - } - // Deserialize - bool GetAioPinsRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("count")) - { - count_ = obj["count"].GetUint(); - } - return true; - } - // Serialize - bool GetAioPinsRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Uint(pin_); - writer->Key("count"); - writer->Uint(count_); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool GetAioPinsRequest::IsNullJSONData() const - { - return false; +void SetDoPinsRequest::set_device(IoDevice device) { device_ = device; } +IoDevice SetDoPinsRequest::device() const { return device_; } +IoDevice *SetDoPinsRequest::mutable_device() { return &device_; } +void SetDoPinsRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int SetDoPinsRequest::pin() const { return pin_; } +unsigned int *SetDoPinsRequest::mutable_pin() { return &pin_; } +void SetDoPinsRequest::set_values(std::vector values) { + values_ = values; +} +std::vector SetDoPinsRequest::values() const { return values_; } +std::vector *SetDoPinsRequest::mutable_values() { + return &values_; +} +// Deserialize +bool SetDoPinsRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } - void GetAioPinsResponse::set_values(std::vector values) - { - values_ = values; - } - std::vector GetAioPinsResponse::values() const - { - return values_; - } - std::vector * GetAioPinsResponse::mutable_values() - { - return &values_; - } - // Deserialize - bool GetAioPinsResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back(i->GetDouble()); - } - values_ = values; - } - return true; - } - // Serialize - bool GetAioPinsResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("values"); - writer->StartArray(); - for(auto i:values_) - { - writer->Double(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - // IsNullJSONData - bool GetAioPinsResponse::IsNullJSONData() const - { - return false; - } - void SetAoPinsRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice SetAoPinsRequest::device() const - { - return device_; - } - IoDevice * SetAoPinsRequest::mutable_device() - { - return &device_; - } - void SetAoPinsRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int SetAoPinsRequest::pin() const - { - return pin_; - } - unsigned int * SetAoPinsRequest::mutable_pin() - { - return &pin_; - } - void SetAoPinsRequest::set_values(std::vector values) - { - values_ = values; - } - std::vector SetAoPinsRequest::values() const - { - return values_; - } - std::vector * SetAoPinsRequest::mutable_values() - { - return &values_; + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back(i->GetUint()); } - // Deserialize - bool SetAoPinsRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back(i->GetDouble()); - } - values_ = values; - } - return true; + values_ = values; + } + return true; +} +// Serialize +bool SetDoPinsRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Int(pin_); + writer->Key("value"); + writer->StartArray(); + for (auto i : values_) { + writer->Uint(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool SetDoPinsRequest::IsNullJSONData() const { return false; } +void GetAioPinsRequest::set_device(IoDevice device) { device_ = device; } +IoDevice GetAioPinsRequest::device() const { return device_; } +IoDevice *GetAioPinsRequest::mutable_device() { return &device_; } +void GetAioPinsRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int GetAioPinsRequest::pin() const { return pin_; } +unsigned int *GetAioPinsRequest::mutable_pin() { return &pin_; } +void GetAioPinsRequest::set_count(unsigned int count) { count_ = count; } +unsigned int GetAioPinsRequest::count() const { return count_; } +unsigned int *GetAioPinsRequest::mutable_count() { return &count_; } +// Deserialize +bool GetAioPinsRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } - // Serialize - bool SetAoPinsRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Int(pin_); - writer->Key("values"); - writer->StartArray(); - for(auto i:values_) - { - writer->Double(i); - } - writer->EndArray(); - writer->EndObject(); - return true; + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("count")) { + count_ = obj["count"].GetUint(); + } + return true; +} +// Serialize +bool GetAioPinsRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Uint(pin_); + writer->Key("count"); + writer->Uint(count_); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetAioPinsRequest::IsNullJSONData() const { return false; } +void GetAioPinsResponse::set_values(std::vector values) { + values_ = values; +} +std::vector GetAioPinsResponse::values() const { return values_; } +std::vector *GetAioPinsResponse::mutable_values() { return &values_; } +// Deserialize +bool GetAioPinsResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back(i->GetDouble()); + } + values_ = values; + } + return true; +} +// Serialize +bool GetAioPinsResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Double(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool GetAioPinsResponse::IsNullJSONData() const { return false; } +void SetAoPinsRequest::set_device(IoDevice device) { device_ = device; } +IoDevice SetAoPinsRequest::device() const { return device_; } +IoDevice *SetAoPinsRequest::mutable_device() { return &device_; } +void SetAoPinsRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int SetAoPinsRequest::pin() const { return pin_; } +unsigned int *SetAoPinsRequest::mutable_pin() { return &pin_; } +void SetAoPinsRequest::set_values(std::vector values) { + values_ = values; +} +std::vector SetAoPinsRequest::values() const { return values_; } +std::vector *SetAoPinsRequest::mutable_values() { return &values_; } +// Deserialize +bool SetAoPinsRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } - // IsNullJSONData - bool SetAoPinsRequest::IsNullJSONData() const - { - return false; + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back(i->GetDouble()); } + values_ = values; + } + return true; +} +// Serialize +bool SetAoPinsRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Int(pin_); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Double(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +// IsNullJSONData +bool SetAoPinsRequest::IsNullJSONData() const { return false; } - void SetDioModeRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice SetDioModeRequest::device() - { - return device_; - } - IoDevice* SetDioModeRequest::mutable_device() - { - return &device_; - } +void SetDioModeRequest::set_device(IoDevice device) { device_ = device; } +IoDevice SetDioModeRequest::device() { return device_; } +IoDevice *SetDioModeRequest::mutable_device() { return &device_; } - void SetDioModeRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int SetDioModeRequest::pin() const - { - return pin_; - } - unsigned int *SetDioModeRequest::mutable_pin() - { - return &pin_; - } +void SetDioModeRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int SetDioModeRequest::pin() const { return pin_; } +unsigned int *SetDioModeRequest::mutable_pin() { return &pin_; } - void SetDioModeRequest::set_value(bool value) - { - value_ = value; - } - bool SetDioModeRequest::value() const - { - return value_; - } - bool *SetDioModeRequest::mutable_value() - { - return &value_; - } +void SetDioModeRequest::set_value(bool value) { value_ = value; } +bool SetDioModeRequest::value() const { return value_; } +bool *SetDioModeRequest::mutable_value() { return &value_; } - bool SetDioModeRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("value")) - { - value_ = obj["value"].GetBool(); - } - return true; - } - bool SetDioModeRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Uint(pin_); - writer->Key("value"); - writer->Bool(value_); - writer->EndObject(); - return true; - } - bool SetDioModeRequest::IsNullJSONData() const - { - return false; +bool SetDioModeRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("value")) { + value_ = obj["value"].GetBool(); + } + return true; +} +bool SetDioModeRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Uint(pin_); + writer->Key("value"); + writer->Bool(value_); + writer->EndObject(); + return true; +} +bool SetDioModeRequest::IsNullJSONData() const { return false; } - void SetDioModeResponse::set_success(bool success) - { - success_ = success; - } - bool SetDioModeResponse::success() const - { - return success_; - } - bool *SetDioModeResponse::mutable_success() - { - return &success_; - } - bool SetDioModeResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("success")) - { - success_ = obj["success"].GetBool(); - } - return true; - } - bool SetDioModeResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("success"); - writer->Bool(success_); - writer->EndObject(); - return true; - } - bool SetDioModeResponse::IsNullJSONData() const - { - return false; - } +void SetDioModeResponse::set_success(bool success) { success_ = success; } +bool SetDioModeResponse::success() const { return success_; } +bool *SetDioModeResponse::mutable_success() { return &success_; } +bool SetDioModeResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("success")) { + success_ = obj["success"].GetBool(); + } + return true; +} +bool SetDioModeResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("success"); + writer->Bool(success_); + writer->EndObject(); + return true; +} +bool SetDioModeResponse::IsNullJSONData() const { return false; } - void SetDioRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice SetDioRequest::device() - { - return device_; - } - IoDevice* SetDioRequest::mutable_device() - { - return &device_; - } - void SetDioRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int SetDioRequest::pin() const - { - return pin_; - } - unsigned int *SetDioRequest::mutable_pin() - { - return &pin_; - } +void SetDioRequest::set_device(IoDevice device) { device_ = device; } +IoDevice SetDioRequest::device() { return device_; } +IoDevice *SetDioRequest::mutable_device() { return &device_; } +void SetDioRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int SetDioRequest::pin() const { return pin_; } +unsigned int *SetDioRequest::mutable_pin() { return &pin_; } - void SetDioRequest::set_value(bool value) - { - value_ = value; - } - bool SetDioRequest::value() const - { - return value_; - } - bool *SetDioRequest::mutable_value() - { - return &value_; - } +void SetDioRequest::set_value(bool value) { value_ = value; } +bool SetDioRequest::value() const { return value_; } +bool *SetDioRequest::mutable_value() { return &value_; } - bool SetDioRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("value")) - { - value_ = obj["value"].GetBool(); - } - return true; - } - bool SetDioRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Uint(pin_); - writer->Key("value"); - writer->Bool(value_); - writer->EndObject(); - return true; - } - bool SetDioRequest::IsNullJSONData() const - { - return false; +bool SetDioRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("value")) { + value_ = obj["value"].GetBool(); + } + return true; +} +bool SetDioRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Uint(pin_); + writer->Key("value"); + writer->Bool(value_); + writer->EndObject(); + return true; +} +bool SetDioRequest::IsNullJSONData() const { return false; } - void SetDioResponse::set_success(bool success) - { - success_ = success; - } - bool SetDioResponse::success() const - { - return success_; - } - bool *SetDioResponse::mutable_success() - { - return &success_; - } - bool SetDioResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("success")) - { - success_ = obj["success"].GetBool(); - } - return true; - } - bool SetDioResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("success"); - writer->Bool(success_); - writer->EndObject(); - return true; - } - bool SetDioResponse::IsNullJSONData() const - { - return false; - } +void SetDioResponse::set_success(bool success) { success_ = success; } +bool SetDioResponse::success() const { return success_; } +bool *SetDioResponse::mutable_success() { return &success_; } +bool SetDioResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("success")) { + success_ = obj["success"].GetBool(); + } + return true; +} +bool SetDioResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("success"); + writer->Bool(success_); + writer->EndObject(); + return true; +} +bool SetDioResponse::IsNullJSONData() const { return false; } - void GetDiosRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int GetDiosRequest::pin() const - { - return pin_; - } - unsigned int *GetDiosRequest::mutable_pin() - { - return &pin_; - } +void GetDiosRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int GetDiosRequest::pin() const { return pin_; } +unsigned int *GetDiosRequest::mutable_pin() { return &pin_; } - void GetDiosRequest::set_count(unsigned int count) - { - count_ = count; - } - unsigned int GetDiosRequest::count() const - { - return count_; - } - unsigned int *GetDiosRequest::mutable_count() - { - return &count_; - } +void GetDiosRequest::set_count(unsigned int count) { count_ = count; } +unsigned int GetDiosRequest::count() const { return count_; } +unsigned int *GetDiosRequest::mutable_count() { return &count_; } - bool GetDiosRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("count")) - { - count_ = obj["count"].GetUint(); - } - return true; - } - bool GetDiosRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("pin"); - writer->Uint(pin_); - writer->Key("count"); - writer->Uint(count_); - writer->EndObject(); - return true; - } - bool GetDiosRequest::IsNullJSONData() const - { - return false; - } +bool GetDiosRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("count")) { + count_ = obj["count"].GetUint(); + } + return true; +} +bool GetDiosRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("pin"); + writer->Uint(pin_); + writer->Key("count"); + writer->Uint(count_); + writer->EndObject(); + return true; +} +bool GetDiosRequest::IsNullJSONData() const { return false; } - void GetDiosResponse::set_values(std::vector values) - { - values_ = values; - } - std::vector GetDiosResponse::values() const - { - return values_; - } - std::vector *GetDiosResponse::mutable_values() - { - return &values_; - } - bool GetDiosResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back(i->GetBool()); - } - values_ = values; - } - return true; - } - bool GetDiosResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("values"); - writer->StartArray(); - for(auto i:values_) - { - writer->Bool(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool GetDiosResponse::IsNullJSONData() const - { - return false; - } +void GetDiosResponse::set_values(std::vector values) { values_ = values; } +std::vector GetDiosResponse::values() const { return values_; } +std::vector *GetDiosResponse::mutable_values() { return &values_; } +bool GetDiosResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back(i->GetBool()); + } + values_ = values; + } + return true; +} +bool GetDiosResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Bool(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool GetDiosResponse::IsNullJSONData() const { return false; } - void GetDiosModeRequest::set_device(IoDevice device) - { - device_ = device; - } - IoDevice GetDiosModeRequest::device() - { - return device_; - } - IoDevice* GetDiosModeRequest::mutable_device() - { - return &device_; - } - void GetDiosModeRequest::set_pin(unsigned int pin) - { - pin_ = pin; - } - unsigned int GetDiosModeRequest::pin() const - { - return pin_; - } - unsigned int *GetDiosModeRequest::mutable_pin() - { - return &pin_; - } +void GetDiosModeRequest::set_device(IoDevice device) { device_ = device; } +IoDevice GetDiosModeRequest::device() { return device_; } +IoDevice *GetDiosModeRequest::mutable_device() { return &device_; } +void GetDiosModeRequest::set_pin(unsigned int pin) { pin_ = pin; } +unsigned int GetDiosModeRequest::pin() const { return pin_; } +unsigned int *GetDiosModeRequest::mutable_pin() { return &pin_; } - void GetDiosModeRequest::set_count(unsigned int count) - { - count_ = count; - } - unsigned int GetDiosModeRequest::count() const - { - return count_; - } - unsigned int *GetDiosModeRequest::mutable_count() - { - return &count_; - } +void GetDiosModeRequest::set_count(unsigned int count) { count_ = count; } +unsigned int GetDiosModeRequest::count() const { return count_; } +unsigned int *GetDiosModeRequest::mutable_count() { return &count_; } - bool GetDiosModeRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - if(device_str == "ROBOT") - { - device_ = ROBOT; - } - else if(device_str == "FLANGE") - { - device_ = FLANGE; - } - else if(device_str == "EXTRA") - { - device_ = EXTRA; - } - } - if(obj.HasMember("pin")) - { - pin_ = obj["pin"].GetUint(); - } - if(obj.HasMember("count")) - { - count_ = obj["count"].GetUint(); - } - return true; - } - bool GetDiosModeRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->Int(device_); - writer->Key("pin"); - writer->Uint(pin_); - writer->Key("count"); - writer->Uint(count_); - writer->EndObject(); - return true; - } - bool GetDiosModeRequest::IsNullJSONData() const - { - return false; +bool GetDiosModeRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + if (device_str == "ROBOT") { + device_ = ROBOT; + } else if (device_str == "FLANGE") { + device_ = FLANGE; + } else if (device_str == "EXTRA") { + device_ = EXTRA; } + } + if (obj.HasMember("pin")) { + pin_ = obj["pin"].GetUint(); + } + if (obj.HasMember("count")) { + count_ = obj["count"].GetUint(); + } + return true; +} +bool GetDiosModeRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->Int(device_); + writer->Key("pin"); + writer->Uint(pin_); + writer->Key("count"); + writer->Uint(count_); + writer->EndObject(); + return true; +} +bool GetDiosModeRequest::IsNullJSONData() const { return false; } - void GetDiosModeResponse::set_values(std::vector values) - { - values_ = values; - } - std::vector GetDiosModeResponse::values() const - { - return values_; - } - std::vector *GetDiosModeResponse::mutable_values() - { - return &values_; - } - bool GetDiosModeResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back(i->GetBool()); - } - values_ = values; - } - return true; - } - bool GetDiosModeResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("values"); - writer->StartArray(); - for(auto i:values_) - { - writer->Bool(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool GetDiosModeResponse::IsNullJSONData() const - { - return false; - } +void GetDiosModeResponse::set_values(std::vector values) { + values_ = values; +} +std::vector GetDiosModeResponse::values() const { return values_; } +std::vector *GetDiosModeResponse::mutable_values() { return &values_; } +bool GetDiosModeResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back(i->GetBool()); + } + values_ = values; + } + return true; +} +bool GetDiosModeResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Bool(i); } -} \ No newline at end of file + writer->EndArray(); + writer->EndObject(); + return true; +} +bool GetDiosModeResponse::IsNullJSONData() const { return false; } +} // namespace io +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/io.hh b/sdk/src/protos/io.hh index 7b35124..b676f38 100644 --- a/sdk/src/protos/io.hh +++ b/sdk/src/protos/io.hh @@ -4,466 +4,466 @@ #include #include -namespace lebai -{ - namespace io - { - - enum IoDevice - { - ROBOT = 0, - FLANGE = 1, - EXTRA = 2, - SHOULDER = 3, - FLANGE_BTN = 4, - }; - enum IoPinKind - { - DI = 0, - DO = 1, - AI = 2, - AO = 3, - }; - /** - * @brief IO related Data . - * - */ - class GetDioPinRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - protected: - IoDevice device_; - unsigned int pin_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - class GetDioPinResponse : public JSONBase - { - public: - void set_value(unsigned int pin); - unsigned int value() const; - unsigned int *mutable_value(); - - protected: - unsigned int value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetDoPinRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_value(unsigned int pin); - unsigned int value() const; - unsigned int *mutable_value(); - - protected: - IoDevice device_; - unsigned int pin_; - unsigned int value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetAioPinRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - protected: - IoDevice device_; - unsigned int pin_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetAioPinResponse : public JSONBase - { - public: - void set_value(double pin); - double value() const; - double *mutable_value(); - - protected: - double value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetAoPinRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_value(double pin); - double value() const; - double *mutable_value(); - - protected: - IoDevice device_; - unsigned int pin_; - double value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetDioPinsRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_count(unsigned int count); - unsigned int count() const; - unsigned int *mutable_count(); - protected: - IoDevice device_; - unsigned int pin_; - unsigned int count_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - class GetDioPinsResponse : public JSONBase - { - public: - void set_values(std::vector pin); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetDoPinsRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_values(std::vector pin); - std::vector values() const; - std::vector *mutable_values(); - - protected: - IoDevice device_; - unsigned int pin_; - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetAioPinsRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_count(unsigned int count); - unsigned int count() const; - unsigned int *mutable_count(); - protected: - IoDevice device_; - unsigned int pin_; - unsigned int count_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetAioPinsResponse : public JSONBase - { - public: - void set_values(std::vector values); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetAoPinsRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device() const; - IoDevice *mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_values(std::vector values); - std::vector values() const; - std::vector *mutable_values(); - - protected: - IoDevice device_; - unsigned int pin_; - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetDioModeRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device(); - IoDevice* mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_value(bool value); - bool value() const; - bool *mutable_value(); - - protected: - IoDevice device_; - unsigned int pin_; - bool value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetDioModeResponse : public JSONBase - { - public: - void set_success(bool success); - bool success() const; - bool *mutable_success(); - - protected: - bool success_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetDioRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device(); - IoDevice* mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_value(bool value); - bool value() const; - bool *mutable_value(); - - protected: - IoDevice device_; - unsigned int pin_; - bool value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetDioResponse : public JSONBase - { - public: - void set_success(bool success); - bool success() const; - bool *mutable_success(); - - protected: - bool success_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetDiosRequest : public JSONBase - { - public: - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_count(unsigned int count); - unsigned int count() const; - unsigned int *mutable_count(); - protected: - unsigned int pin_; - unsigned int count_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - class GetDiosResponse : public JSONBase - { - public: - void set_values(std::vector pin); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetDiosModeRequest : public JSONBase - { - public: - void set_device(IoDevice device); - IoDevice device(); - IoDevice* mutable_device(); - - void set_pin(unsigned int pin); - unsigned int pin() const; - unsigned int *mutable_pin(); - - void set_count(unsigned int count); - unsigned int count() const; - unsigned int *mutable_count(); - protected: - IoDevice device_; - unsigned int pin_; - unsigned int count_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - class GetDiosModeResponse : public JSONBase - { - public: - void set_values(std::vector pin); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - } -} \ No newline at end of file +namespace lebai { +namespace io { + +enum IoDevice { + ROBOT = 0, + FLANGE = 1, + EXTRA = 2, + SHOULDER = 3, + FLANGE_BTN = 4, +}; +enum IoPinKind { + DI = 0, + DO = 1, + AI = 2, + AO = 3, +}; +/** + * @brief IO related Data . + * + */ +class GetDioPinRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + protected: + IoDevice device_; + unsigned int pin_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +class GetDioPinResponse : public JSONBase { + public: + void set_value(unsigned int pin); + unsigned int value() const; + unsigned int *mutable_value(); + + protected: + unsigned int value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetDoPinRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_value(unsigned int pin); + unsigned int value() const; + unsigned int *mutable_value(); + + protected: + IoDevice device_; + unsigned int pin_; + unsigned int value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetAioPinRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + protected: + IoDevice device_; + unsigned int pin_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetAioPinResponse : public JSONBase { + public: + void set_value(double pin); + double value() const; + double *mutable_value(); + + protected: + double value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetAoPinRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_value(double pin); + double value() const; + double *mutable_value(); + + protected: + IoDevice device_; + unsigned int pin_; + double value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetDioPinsRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_count(unsigned int count); + unsigned int count() const; + unsigned int *mutable_count(); + + protected: + IoDevice device_; + unsigned int pin_; + unsigned int count_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +class GetDioPinsResponse : public JSONBase { + public: + void set_values(std::vector pin); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetDoPinsRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_values(std::vector pin); + std::vector values() const; + std::vector *mutable_values(); + + protected: + IoDevice device_; + unsigned int pin_; + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetAioPinsRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_count(unsigned int count); + unsigned int count() const; + unsigned int *mutable_count(); + + protected: + IoDevice device_; + unsigned int pin_; + unsigned int count_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetAioPinsResponse : public JSONBase { + public: + void set_values(std::vector values); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetAoPinsRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device() const; + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_values(std::vector values); + std::vector values() const; + std::vector *mutable_values(); + + protected: + IoDevice device_; + unsigned int pin_; + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetDioModeRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device(); + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_value(bool value); + bool value() const; + bool *mutable_value(); + + protected: + IoDevice device_; + unsigned int pin_; + bool value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetDioModeResponse : public JSONBase { + public: + void set_success(bool success); + bool success() const; + bool *mutable_success(); + + protected: + bool success_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetDioRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device(); + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_value(bool value); + bool value() const; + bool *mutable_value(); + + protected: + IoDevice device_; + unsigned int pin_; + bool value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetDioResponse : public JSONBase { + public: + void set_success(bool success); + bool success() const; + bool *mutable_success(); + + protected: + bool success_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetDiosRequest : public JSONBase { + public: + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_count(unsigned int count); + unsigned int count() const; + unsigned int *mutable_count(); + + protected: + unsigned int pin_; + unsigned int count_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +class GetDiosResponse : public JSONBase { + public: + void set_values(std::vector pin); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetDiosModeRequest : public JSONBase { + public: + void set_device(IoDevice device); + IoDevice device(); + IoDevice *mutable_device(); + + void set_pin(unsigned int pin); + unsigned int pin() const; + unsigned int *mutable_pin(); + + void set_count(unsigned int count); + unsigned int count() const; + unsigned int *mutable_count(); + + protected: + IoDevice device_; + unsigned int pin_; + unsigned int count_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +class GetDiosModeResponse : public JSONBase { + public: + void set_values(std::vector pin); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +} // namespace io +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/jsonbase.cc b/sdk/src/protos/jsonbase.cc index da55869..1960607 100644 --- a/sdk/src/protos/jsonbase.cc +++ b/sdk/src/protos/jsonbase.cc @@ -1,30 +1,24 @@ -# include "jsonbase.hh" #include -#include -#include -#include - - -namespace lebai -{ - - -std::string JSONBase::ToJSONString() const -{ - rapidjson::StringBuffer ss; - rapidjson::Writer writer(ss); // Can also use writer for condensed formatting - if (Serialize(&writer)) - { - return std::string(ss.GetString()); - } - return ""; +#include "jsonbase.hh" + +namespace lebai { + +std::string JSONBase::ToJSONString() const { + rapidjson::StringBuffer ss; + rapidjson::Writer writer( + ss); // Can also use writer for condensed formatting + if (Serialize(&writer)) { + return std::string(ss.GetString()); + } + return ""; } -// std::string JSONBase::ToJSONRpcReqString(const std::string & method, int id) const +// std::string JSONBase::ToJSONRpcReqString(const std::string & method, int id) +// const // { // rapidjson::StringBuffer ss; -// rapidjson::Writer writer(ss); // Can also use Writer for condensed formatting -// writer.StartObject(); +// rapidjson::Writer writer(ss); // Can +// also use Writer for condensed formatting writer.StartObject(); // writer.String("jsonrpc"); // writer.String("2.0"); // writer.String("method"); @@ -37,15 +31,13 @@ std::string JSONBase::ToJSONString() const // return std::string(ss.GetString()); // } -bool JSONBase::FromJSONString(const std::string& s) -{ - rapidjson::Document doc; - if (!InitDocument(s, doc)) - return false; +bool JSONBase::FromJSONString(const std::string& s) { + rapidjson::Document doc; + if (!InitDocument(s, doc)) return false; - Deserialize(doc); + Deserialize(doc); - return true; + return true; } // bool JSONBase::FromJSONRpcRespString(const std::string &s) @@ -59,8 +51,8 @@ bool JSONBase::FromJSONString(const std::string& s) // // Error code and message. // int error_id = doc["error"]["code"].GetInt(); // std::string error_msg = doc["error"]["message"].GetString(); -// std::cout << "Error: " << error_id << " " << error_msg << std::endl; -// return false; +// std::cout << "Error: " << error_id << " " << error_msg << +// std::endl; return false; // } // if (doc.HasMember("result")) @@ -76,13 +68,11 @@ bool JSONBase::FromJSONString(const std::string& s) // return ToJSONString().c_str(); // } -bool JSONBase::InitDocument(const std::string& s, rapidjson::Document& doc) -{ - if (s.empty()) - return false; +bool JSONBase::InitDocument(const std::string& s, rapidjson::Document& doc) { + if (s.empty()) return false; - std::string validJson(s); + std::string validJson(s); - return !doc.Parse(validJson.c_str()).HasParseError() ? true : false; + return !doc.Parse(validJson.c_str()).HasParseError() ? true : false; } -} \ No newline at end of file +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/jsonbase.hh b/sdk/src/protos/jsonbase.hh index 31a6b79..a1d2a3d 100644 --- a/sdk/src/protos/jsonbase.hh +++ b/sdk/src/protos/jsonbase.hh @@ -2,27 +2,26 @@ #include #include "rapidjson/rapidjson.h" -#include "rapidjson/document.h" // rapidjson's DOM-style API -#include "rapidjson/stringbuffer.h" // wrapper of C stream for prettywriter as output -#include "rapidjson/prettywriter.h" // for stringify JSON +#include "rapidjson/document.h" // rapidjson's DOM-style API +#include "rapidjson/stringbuffer.h" // wrapper of C stream for prettywriter as output +#include "rapidjson/prettywriter.h" // for stringify JSON -namespace lebai -{ - - class JSONBase - { - public: - std::string ToJSONString() const; - // std::string ToJSONRpcReqString(const std::string & method, int id) const; - bool FromJSONString(const std::string &s); - // bool FromJSONRpcRespString(const std::string &s); - // virtual const char * ToString() const; - virtual bool Deserialize(const rapidjson::Value &obj) = 0; - virtual bool Serialize(rapidjson::Writer *writer) const = 0; - virtual bool IsNullJSONData() const = 0; +namespace lebai { + +class JSONBase { + public: + std::string ToJSONString() const; + // std::string ToJSONRpcReqString(const std::string & method, int id) const; + bool FromJSONString(const std::string &s); + // bool FromJSONRpcRespString(const std::string &s); + // virtual const char * ToString() const; + virtual bool Deserialize(const rapidjson::Value &obj) = 0; + virtual bool Serialize( + rapidjson::Writer *writer) const = 0; + virtual bool IsNullJSONData() const = 0; // public: - bool InitDocument(const std::string &s, rapidjson::Document &doc); - // std::string internal_json_string_; - }; + bool InitDocument(const std::string &s, rapidjson::Document &doc); + // std::string internal_json_string_; +}; -} // namespace lebai +} // namespace lebai diff --git a/sdk/src/protos/kinematic.cc b/sdk/src/protos/kinematic.cc index 3e4347d..6609e75 100755 --- a/sdk/src/protos/kinematic.cc +++ b/sdk/src/protos/kinematic.cc @@ -2,377 +2,318 @@ #include #include "kinematic.hh" +namespace lebai { +namespace kinematic { +KinData &KinData::operator=(const KinData &other) { + actual_joint_pose_ = other.actual_joint_pose_; + actual_joint_speed_ = other.actual_joint_speed_; + actual_joint_acc_ = other.actual_joint_acc_; + actual_joint_torque_ = other.actual_joint_torque_; + target_joint_pose_ = other.target_joint_pose_; + target_joint_speed_ = other.target_joint_speed_; + target_joint_acc_ = other.target_joint_acc_; + target_joint_torque_ = other.target_joint_torque_; + // actual_tcp_pose_ = other.actual_tcp_pose_; + // target_tcp_pose_ = other.target_tcp_pose_; + // actual_flange_pose_ = other.actual_flange_pose_; + return *this; +} +void KinData::set_actual_joint_pose( + const std::vector &actual_joint_pose) { + actual_joint_pose_ = actual_joint_pose; +} +const std::vector &KinData::actual_joint_pose() const { + return actual_joint_pose_; +} +std::vector *KinData::mutable_actual_joint_pose() { + return &actual_joint_pose_; +} +void KinData::set_actual_joint_speed( + const std::vector &actual_joint_speed) { + actual_joint_speed_ = actual_joint_speed; +} +const std::vector &KinData::actual_joint_speed() const { + return actual_joint_speed_; +} +std::vector *KinData::mutable_actual_joint_speed() { + return &actual_joint_speed_; +} +void KinData::set_actual_joint_acc( + const std::vector &actual_joint_acc) { + actual_joint_acc_ = actual_joint_acc; +} +const std::vector &KinData::actual_joint_acc() const { + return actual_joint_acc_; +} +std::vector *KinData::mutable_actual_joint_acc() { + return &actual_joint_acc_; +} +void KinData::set_actual_joint_torque( + const std::vector &actual_joint_torque) { + actual_joint_torque_ = actual_joint_torque; +} +const std::vector &KinData::actual_joint_torque() const { + return actual_joint_torque_; +} +std::vector *KinData::mutable_actual_joint_torque() { + return &actual_joint_torque_; +} +void KinData::set_target_joint_pose( + const std::vector &target_joint_pose) { + target_joint_pose_ = target_joint_pose; +} +const std::vector &KinData::target_joint_pose() const { + return target_joint_pose_; +} +std::vector *KinData::mutable_target_joint_pose() { + return &target_joint_pose_; +} +void KinData::set_target_joint_speed( + const std::vector &target_joint_speed) { + target_joint_speed_ = target_joint_speed; +} +const std::vector &KinData::target_joint_speed() const { + return target_joint_speed_; +} +std::vector *KinData::mutable_target_joint_speed() { + return &target_joint_speed_; +} +void KinData::set_target_joint_acc( + const std::vector &target_joint_acc) { + target_joint_acc_ = target_joint_acc; +} +const std::vector &KinData::target_joint_acc() const { + return target_joint_acc_; +} +std::vector *KinData::mutable_target_joint_acc() { + return &target_joint_acc_; +} +void KinData::set_target_joint_torque( + const std::vector &target_joint_torque) { + target_joint_torque_ = target_joint_torque; +} +const std::vector &KinData::target_joint_torque() const { + return target_joint_torque_; +} +std::vector *KinData::mutable_target_joint_torque() { + return &target_joint_torque_; +} +void KinData::set_actual_tcp_pose( + const posture::CartesianPose &actual_tcp_pose) { + actual_tcp_pose_ = actual_tcp_pose; +} +const posture::CartesianPose &KinData::actual_tcp_pose() const { + return actual_tcp_pose_; +} +posture::CartesianPose *KinData::mutable_actual_tcp_pose() { + return &actual_tcp_pose_; +} +// target_tcp_pose_ +void KinData::set_target_tcp_pose( + const posture::CartesianPose &target_tcp_pose) { + target_tcp_pose_ = target_tcp_pose; +} +const posture::CartesianPose &KinData::target_tcp_pose() const { + return target_tcp_pose_; +} +posture::CartesianPose *KinData::mutable_target_tcp_pose() { + return &target_tcp_pose_; +} +// actual_flange_pose_ +void KinData::set_actual_flange_pose( + const posture::CartesianPose &actual_flange_pose) { + actual_flange_pose_ = actual_flange_pose; +} +const posture::CartesianPose &KinData::actual_flange_pose() const { + return actual_flange_pose_; +} +posture::CartesianPose *KinData::mutable_actual_flange_pose() { + return &actual_flange_pose_; +} +// Deserialize +bool KinData::Deserialize(const rapidjson::Value &obj) { + actual_joint_pose_.clear(); + for (auto iter = obj["actual_joint_pose"].GetArray().Begin(); + iter != obj["actual_joint_pose"].GetArray().End(); iter++) { + actual_joint_pose_.push_back(iter->GetDouble()); + } + actual_joint_speed_.clear(); + for (auto iter = obj["actual_joint_speed"].GetArray().Begin(); + iter != obj["actual_joint_speed"].GetArray().End(); iter++) { + actual_joint_speed_.push_back(iter->GetDouble()); + } + actual_joint_acc_.clear(); + for (auto iter = obj["actual_joint_acc"].GetArray().Begin(); + iter != obj["actual_joint_acc"].GetArray().End(); iter++) { + actual_joint_acc_.push_back(iter->GetDouble()); + } + actual_joint_torque_.clear(); + for (auto iter = obj["actual_joint_torque"].GetArray().Begin(); + iter != obj["actual_joint_torque"].GetArray().End(); iter++) { + actual_joint_torque_.push_back(iter->GetDouble()); + } + target_joint_pose_.clear(); + for (auto iter = obj["target_joint_pose"].GetArray().Begin(); + iter != obj["target_joint_pose"].GetArray().End(); iter++) { + target_joint_pose_.push_back(iter->GetDouble()); + } + target_joint_speed_.clear(); + for (auto iter = obj["target_joint_speed"].GetArray().Begin(); + iter != obj["target_joint_speed"].GetArray().End(); iter++) { + target_joint_speed_.push_back(iter->GetDouble()); + } + target_joint_acc_.clear(); + for (auto iter = obj["target_joint_acc"].GetArray().Begin(); + iter != obj["target_joint_acc"].GetArray().End(); iter++) { + target_joint_acc_.push_back(iter->GetDouble()); + } + target_joint_torque_.clear(); + for (auto iter = obj["target_joint_torque"].GetArray().Begin(); + iter != obj["target_joint_torque"].GetArray().End(); iter++) { + target_joint_torque_.push_back(iter->GetDouble()); + } + if (obj.HasMember("actual_tcp_pose")) { + actual_tcp_pose_.Deserialize(obj["actual_tcp_pose"]); + } + if (obj.HasMember("target_tcp_pose")) { + target_tcp_pose_.Deserialize(obj["target_tcp_pose"]); + } + if (!obj.HasMember("actual_flange_pose")) { + actual_flange_pose_.Deserialize(obj["actual_flange_pose"]); + } + return true; +} +// Serialize +bool KinData::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("actual_joint_pose"); + writer->StartArray(); + for (auto iter = actual_joint_pose_.begin(); iter != actual_joint_pose_.end(); + iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->Key("actual_joint_speed"); + writer->StartArray(); + for (auto iter = actual_joint_speed_.begin(); + iter != actual_joint_speed_.end(); iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->Key("actual_joint_acc"); + writer->StartArray(); + for (auto iter = actual_joint_acc_.begin(); iter != actual_joint_acc_.end(); + iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->Key("actual_joint_torque"); + writer->StartArray(); + for (auto iter = actual_joint_torque_.begin(); + iter != actual_joint_torque_.end(); iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->Key("target_joint_pose"); + writer->StartArray(); + for (auto iter = target_joint_pose_.begin(); iter != target_joint_pose_.end(); + iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->Key("target_joint_speed"); + writer->StartArray(); + for (auto iter = target_joint_speed_.begin(); + iter != target_joint_speed_.end(); iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->Key("target_joint_acc"); + writer->StartArray(); + for (auto iter = target_joint_acc_.begin(); iter != target_joint_acc_.end(); + iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->Key("target_joint_torque"); + writer->StartArray(); + for (auto iter = target_joint_torque_.begin(); + iter != target_joint_torque_.end(); iter++) { + writer->Double(*iter); + } + writer->EndArray(); + if (!actual_tcp_pose_.IsNullJSONData()) { + writer->Key("actual_tcp_pose"); + actual_tcp_pose_.Serialize(writer); + } + if (!target_tcp_pose_.IsNullJSONData()) { + writer->Key("target_tcp_pose"); + target_tcp_pose_.Serialize(writer); + } + if (!actual_flange_pose_.IsNullJSONData()) { + writer->Key("actual_flange_pose"); + actual_flange_pose_.Serialize(writer); + } + writer->EndObject(); + return true; +} +// IsNullJSONData +bool KinData::IsNullJSONData() const { + if (actual_joint_pose_.size() > 0) { + return false; + } + if (actual_joint_speed_.size() > 0) { + return false; + } + if (actual_joint_acc_.size() > 0) { + return false; + } + if (actual_joint_torque_.size() > 0) { + return false; + } + if (target_joint_pose_.size() > 0) { + return false; + } + if (target_joint_speed_.size() > 0) { + return false; + } + if (target_joint_acc_.size() > 0) { + return false; + } + if (target_joint_torque_.size() > 0) { + return false; + } + if (!actual_tcp_pose_.IsNullJSONData()) { + return false; + } + if (!target_tcp_pose_.IsNullJSONData()) { + return false; + } + if (!actual_flange_pose_.IsNullJSONData()) { + return false; + } + return true; +} -namespace lebai -{ - namespace kinematic - { - KinData & KinData::operator = (const KinData & other) - { - actual_joint_pose_ = other.actual_joint_pose_; - actual_joint_speed_ = other.actual_joint_speed_; - actual_joint_acc_ = other.actual_joint_acc_; - actual_joint_torque_ = other.actual_joint_torque_; - target_joint_pose_ = other.target_joint_pose_; - target_joint_speed_ = other.target_joint_speed_; - target_joint_acc_ = other.target_joint_acc_; - target_joint_torque_ = other.target_joint_torque_; - // actual_tcp_pose_ = other.actual_tcp_pose_; - // target_tcp_pose_ = other.target_tcp_pose_; - // actual_flange_pose_ = other.actual_flange_pose_; - return *this; - } - void KinData::set_actual_joint_pose(const std::vector & actual_joint_pose) - { - actual_joint_pose_ = actual_joint_pose; - } - const std::vector & KinData::actual_joint_pose() const - { - return actual_joint_pose_; - } - std::vector * KinData::mutable_actual_joint_pose() - { - return &actual_joint_pose_; - } - void KinData::set_actual_joint_speed(const std::vector & actual_joint_speed) - { - actual_joint_speed_ = actual_joint_speed; - } - const std::vector & KinData::actual_joint_speed() const - { - return actual_joint_speed_; - } - std::vector * KinData::mutable_actual_joint_speed() - { - return &actual_joint_speed_; - } - void KinData::set_actual_joint_acc(const std::vector & actual_joint_acc) - { - actual_joint_acc_ = actual_joint_acc; - } - const std::vector & KinData::actual_joint_acc() const - { - return actual_joint_acc_; - } - std::vector * KinData::mutable_actual_joint_acc() - { - return &actual_joint_acc_; - } - void KinData::set_actual_joint_torque(const std::vector & actual_joint_torque) - { - actual_joint_torque_ = actual_joint_torque; - } - const std::vector & KinData::actual_joint_torque() const - { - return actual_joint_torque_; - } - std::vector * KinData::mutable_actual_joint_torque() - { - return &actual_joint_torque_; - } - void KinData::set_target_joint_pose(const std::vector & target_joint_pose) - { - target_joint_pose_ = target_joint_pose; - } - const std::vector & KinData::target_joint_pose() const - { - return target_joint_pose_; - } - std::vector * KinData::mutable_target_joint_pose() - { - return &target_joint_pose_; - } - void KinData::set_target_joint_speed(const std::vector & target_joint_speed) - { - target_joint_speed_ = target_joint_speed; - } - const std::vector & KinData::target_joint_speed() const - { - return target_joint_speed_; - } - std::vector * KinData::mutable_target_joint_speed() - { - return &target_joint_speed_; - } - void KinData::set_target_joint_acc(const std::vector & target_joint_acc) - { - target_joint_acc_ = target_joint_acc; - } - const std::vector & KinData::target_joint_acc() const - { - return target_joint_acc_; - } - std::vector * KinData::mutable_target_joint_acc() - { - return &target_joint_acc_; - } - void KinData::set_target_joint_torque(const std::vector & target_joint_torque) - { - target_joint_torque_ = target_joint_torque; - } - const std::vector & KinData::target_joint_torque() const - { - return target_joint_torque_; - } - std::vector * KinData::mutable_target_joint_torque() - { - return &target_joint_torque_; - } - void KinData::set_actual_tcp_pose(const posture::CartesianPose & actual_tcp_pose) - { - actual_tcp_pose_ = actual_tcp_pose; - } - const posture::CartesianPose & KinData::actual_tcp_pose() const - { - return actual_tcp_pose_; - } - posture::CartesianPose * KinData::mutable_actual_tcp_pose() - { - return &actual_tcp_pose_; - } - // target_tcp_pose_ - void KinData::set_target_tcp_pose(const posture::CartesianPose & target_tcp_pose) - { - target_tcp_pose_ = target_tcp_pose; - } - const posture::CartesianPose & KinData::target_tcp_pose() const - { - return target_tcp_pose_; - } - posture::CartesianPose * KinData::mutable_target_tcp_pose() - { - return &target_tcp_pose_; - } - // actual_flange_pose_ - void KinData::set_actual_flange_pose(const posture::CartesianPose & actual_flange_pose) - { - actual_flange_pose_ = actual_flange_pose; - } - const posture::CartesianPose & KinData::actual_flange_pose() const - { - return actual_flange_pose_; - } - posture::CartesianPose * KinData::mutable_actual_flange_pose() - { - return &actual_flange_pose_; - } - // Deserialize - bool KinData::Deserialize(const rapidjson::Value &obj) - { - actual_joint_pose_.clear(); - for(auto iter = obj["actual_joint_pose"].GetArray().Begin(); iter != obj["actual_joint_pose"].GetArray().End(); iter++) - { - actual_joint_pose_.push_back(iter->GetDouble()); - } - actual_joint_speed_.clear(); - for(auto iter = obj["actual_joint_speed"].GetArray().Begin(); iter != obj["actual_joint_speed"].GetArray().End(); iter++) - { - actual_joint_speed_.push_back(iter->GetDouble()); - } - actual_joint_acc_.clear(); - for(auto iter = obj["actual_joint_acc"].GetArray().Begin(); iter != obj["actual_joint_acc"].GetArray().End(); iter++) - { - actual_joint_acc_.push_back(iter->GetDouble()); - } - actual_joint_torque_.clear(); - for(auto iter = obj["actual_joint_torque"].GetArray().Begin(); iter != obj["actual_joint_torque"].GetArray().End(); iter++) - { - actual_joint_torque_.push_back(iter->GetDouble()); - } - target_joint_pose_.clear(); - for(auto iter = obj["target_joint_pose"].GetArray().Begin(); iter != obj["target_joint_pose"].GetArray().End(); iter++) - { - target_joint_pose_.push_back(iter->GetDouble()); - } - target_joint_speed_.clear(); - for(auto iter = obj["target_joint_speed"].GetArray().Begin(); iter != obj["target_joint_speed"].GetArray().End(); iter++) - { - target_joint_speed_.push_back(iter->GetDouble()); - } - target_joint_acc_.clear(); - for(auto iter = obj["target_joint_acc"].GetArray().Begin(); iter != obj["target_joint_acc"].GetArray().End(); iter++) - { - target_joint_acc_.push_back(iter->GetDouble()); - } - target_joint_torque_.clear(); - for(auto iter = obj["target_joint_torque"].GetArray().Begin(); iter != obj["target_joint_torque"].GetArray().End(); iter++) - { - target_joint_torque_.push_back(iter->GetDouble()); - } - if(obj.HasMember("actual_tcp_pose")) - { - actual_tcp_pose_.Deserialize(obj["actual_tcp_pose"]); - } - if(obj.HasMember("target_tcp_pose")) - { - target_tcp_pose_.Deserialize(obj["target_tcp_pose"]); - } - if(!obj.HasMember("actual_flange_pose")) - { - actual_flange_pose_.Deserialize(obj["actual_flange_pose"]); - } - return true; - } - // Serialize - bool KinData::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("actual_joint_pose"); - writer->StartArray(); - for(auto iter = actual_joint_pose_.begin(); iter != actual_joint_pose_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->Key("actual_joint_speed"); - writer->StartArray(); - for(auto iter = actual_joint_speed_.begin(); iter != actual_joint_speed_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->Key("actual_joint_acc"); - writer->StartArray(); - for(auto iter = actual_joint_acc_.begin(); iter != actual_joint_acc_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->Key("actual_joint_torque"); - writer->StartArray(); - for(auto iter = actual_joint_torque_.begin(); iter != actual_joint_torque_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->Key("target_joint_pose"); - writer->StartArray(); - for(auto iter = target_joint_pose_.begin(); iter != target_joint_pose_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->Key("target_joint_speed"); - writer->StartArray(); - for(auto iter = target_joint_speed_.begin(); iter != target_joint_speed_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->Key("target_joint_acc"); - writer->StartArray(); - for(auto iter = target_joint_acc_.begin(); iter != target_joint_acc_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->Key("target_joint_torque"); - writer->StartArray(); - for(auto iter = target_joint_torque_.begin(); iter != target_joint_torque_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - if(!actual_tcp_pose_.IsNullJSONData()) - { - writer->Key("actual_tcp_pose"); - actual_tcp_pose_.Serialize(writer); - } - if(!target_tcp_pose_.IsNullJSONData()) - { - writer->Key("target_tcp_pose"); - target_tcp_pose_.Serialize(writer); - } - if(!actual_flange_pose_.IsNullJSONData()) - { - writer->Key("actual_flange_pose"); - actual_flange_pose_.Serialize(writer); - } - writer->EndObject(); - return true; - } - // IsNullJSONData - bool KinData::IsNullJSONData() const - { - if(actual_joint_pose_.size() > 0) - { - return false; - } - if(actual_joint_speed_.size() > 0) - { - return false; - } - if(actual_joint_acc_.size() > 0) - { - return false; - } - if(actual_joint_torque_.size() > 0) - { - return false; - } - if(target_joint_pose_.size() > 0) - { - return false; - } - if(target_joint_speed_.size() > 0) - { - return false; - } - if(target_joint_acc_.size() > 0) - { - return false; - } - if(target_joint_torque_.size() > 0) - { - return false; - } - if(!actual_tcp_pose_.IsNullJSONData()) - { - return false; - } - if(!target_tcp_pose_.IsNullJSONData()) - { - return false; - } - if(!actual_flange_pose_.IsNullJSONData()) - { - return false; - } - return true; - } - - void KinFactor::set_factor(int factor) - { - factor_ = factor; - } - int KinFactor::factor() - { - return factor_; - } - int * KinFactor::mutable_factor() - { - return &factor_; - } - bool KinFactor::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("speed_factor")) - { - int factor = (int)(obj["speed_factor"].GetInt()); - factor_ = factor; - } - return true; - } - bool KinFactor::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("speed_factor"); - writer->Int(factor_); - writer->EndObject(); - return true; - } - bool KinFactor::IsNullJSONData() const - { - return false; - } - } -} \ No newline at end of file +void KinFactor::set_factor(int factor) { factor_ = factor; } +int KinFactor::factor() { return factor_; } +int *KinFactor::mutable_factor() { return &factor_; } +bool KinFactor::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("speed_factor")) { + int factor = (int)(obj["speed_factor"].GetInt()); + factor_ = factor; + } + return true; +} +bool KinFactor::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("speed_factor"); + writer->Int(factor_); + writer->EndObject(); + return true; +} +bool KinFactor::IsNullJSONData() const { return false; } +} // namespace kinematic +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/kinematic.hh b/sdk/src/protos/kinematic.hh index c60b48f..fb13cc6 100644 --- a/sdk/src/protos/kinematic.hh +++ b/sdk/src/protos/kinematic.hh @@ -6,152 +6,152 @@ #include #include "posture.hh" -namespace lebai -{ - namespace kinematic - { +namespace lebai { +namespace kinematic { - /** - * @brief Data to represent a joint array data. - * - */ - class KinData : public JSONBase - { - public: - // KinData() = default; - // KinData(const KinData & other) = default; - KinData & operator = (const KinData & other); - void set_actual_joint_pose(const std::vector & actual_joint_pose); - const std::vector & actual_joint_pose() const; - std::vector * mutable_actual_joint_pose(); - void set_actual_joint_speed(const std::vector & actual_joint_speed); - const std::vector & actual_joint_speed() const; - std::vector * mutable_actual_joint_speed(); - void set_actual_joint_acc(const std::vector & actual_joint_acc); - const std::vector & actual_joint_acc() const; - std::vector * mutable_actual_joint_acc(); - void set_actual_joint_torque(const std::vector & actual_joint_torque); - const std::vector & actual_joint_torque() const; - std::vector * mutable_actual_joint_torque(); +/** + * @brief Data to represent a joint array data. + * + */ +class KinData : public JSONBase { + public: + // KinData() = default; + // KinData(const KinData & other) = default; + KinData &operator=(const KinData &other); + void set_actual_joint_pose(const std::vector &actual_joint_pose); + const std::vector &actual_joint_pose() const; + std::vector *mutable_actual_joint_pose(); + void set_actual_joint_speed(const std::vector &actual_joint_speed); + const std::vector &actual_joint_speed() const; + std::vector *mutable_actual_joint_speed(); + void set_actual_joint_acc(const std::vector &actual_joint_acc); + const std::vector &actual_joint_acc() const; + std::vector *mutable_actual_joint_acc(); + void set_actual_joint_torque(const std::vector &actual_joint_torque); + const std::vector &actual_joint_torque() const; + std::vector *mutable_actual_joint_torque(); - void set_target_joint_pose(const std::vector & target_joint_pose); - const std::vector & target_joint_pose() const; - std::vector * mutable_target_joint_pose(); - void set_target_joint_speed(const std::vector & target_joint_speed); - const std::vector & target_joint_speed() const; - std::vector * mutable_target_joint_speed(); - void set_target_joint_acc(const std::vector & target_joint_acc); - const std::vector & target_joint_acc() const; - std::vector * mutable_target_joint_acc(); - void set_target_joint_torque(const std::vector & target_joint_torque); - const std::vector & target_joint_torque() const; - std::vector * mutable_target_joint_torque(); - - void set_actual_tcp_pose(const posture::CartesianPose & actual_tcp_pose); - const posture::CartesianPose & actual_tcp_pose() const; - posture::CartesianPose * mutable_actual_tcp_pose(); - void set_target_tcp_pose(const posture::CartesianPose & target_tcp_pose); - const posture::CartesianPose & target_tcp_pose() const; - posture::CartesianPose * mutable_target_tcp_pose(); - void set_actual_flange_pose(const posture::CartesianPose & actual_flange_pose); - const posture::CartesianPose & actual_flange_pose() const; - posture::CartesianPose * mutable_actual_flange_pose(); + void set_target_joint_pose(const std::vector &target_joint_pose); + const std::vector &target_joint_pose() const; + std::vector *mutable_target_joint_pose(); + void set_target_joint_speed(const std::vector &target_joint_speed); + const std::vector &target_joint_speed() const; + std::vector *mutable_target_joint_speed(); + void set_target_joint_acc(const std::vector &target_joint_acc); + const std::vector &target_joint_acc() const; + std::vector *mutable_target_joint_acc(); + void set_target_joint_torque(const std::vector &target_joint_torque); + const std::vector &target_joint_torque() const; + std::vector *mutable_target_joint_torque(); - protected: - std::vector actual_joint_pose_; - std::vector actual_joint_speed_; - std::vector actual_joint_acc_; - std::vector actual_joint_torque_; - std::vector target_joint_pose_; - std::vector target_joint_speed_; - std::vector target_joint_acc_; - std::vector target_joint_torque_; - posture::CartesianPose actual_tcp_pose_; - posture::CartesianPose target_tcp_pose_; - posture::CartesianPose actual_flange_pose_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; + void set_actual_tcp_pose(const posture::CartesianPose &actual_tcp_pose); + const posture::CartesianPose &actual_tcp_pose() const; + posture::CartesianPose *mutable_actual_tcp_pose(); + void set_target_tcp_pose(const posture::CartesianPose &target_tcp_pose); + const posture::CartesianPose &target_tcp_pose() const; + posture::CartesianPose *mutable_target_tcp_pose(); + void set_actual_flange_pose(const posture::CartesianPose &actual_flange_pose); + const posture::CartesianPose &actual_flange_pose() const; + posture::CartesianPose *mutable_actual_flange_pose(); - // class KinData : public JSONBase - // { - // public: - // // KinData() = default; - // // KinData(const KinData & other) = default; - // KinData & operator = (const KinData & other); - // void set_actual_joint_pose(const std::vector & actual_joint_pose); - // const std::vector & actual_joint_pose() const; - // std::vector * mutable_actual_joint_pose(); - // void set_actual_joint_speed(const std::vector & actual_joint_speed); - // const std::vector & actual_joint_speed() const; - // std::vector * mutable_actual_joint_speed(); - // void set_actual_joint_acc(const std::vector & actual_joint_acc); - // const std::vector & actual_joint_acc() const; - // std::vector * mutable_actual_joint_acc(); - // void set_actual_joint_torque(const std::vector & actual_joint_torque); - // const std::vector & actual_joint_torque() const; - // std::vector * mutable_actual_joint_torque(); + protected: + std::vector actual_joint_pose_; + std::vector actual_joint_speed_; + std::vector actual_joint_acc_; + std::vector actual_joint_torque_; + std::vector target_joint_pose_; + std::vector target_joint_speed_; + std::vector target_joint_acc_; + std::vector target_joint_torque_; + posture::CartesianPose actual_tcp_pose_; + posture::CartesianPose target_tcp_pose_; + posture::CartesianPose actual_flange_pose_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - // void set_target_joint_pose(const std::vector & target_joint_pose); - // const std::vector & target_joint_pose() const; - // std::vector * mutable_target_joint_pose(); - // void set_target_joint_speed(const std::vector & target_joint_speed); - // const std::vector & target_joint_speed() const; - // std::vector * mutable_target_joint_speed(); - // void set_target_joint_acc(const std::vector & target_joint_acc); - // const std::vector & target_joint_acc() const; - // std::vector * mutable_target_joint_acc(); - // void set_target_joint_torque(const std::vector & target_joint_torque); - // const std::vector & target_joint_torque() const; - // std::vector * mutable_target_joint_torque(); - - // void set_actual_tcp_pose(const posture::CartesianPose & actual_tcp_pose); - // const posture::CartesianPose & actual_tcp_pose() const; - // posture::CartesianPose * mutable_actual_tcp_pose(); - // void set_target_tcp_pose(const posture::CartesianPose & target_tcp_pose); - // const posture::CartesianPose & target_tcp_pose() const; - // posture::CartesianPose * mutable_target_tcp_pose(); - // void set_actual_flange_pose(const posture::CartesianPose & actual_flange_pose); - // const posture::CartesianPose & actual_flange_pose() const; - // posture::CartesianPose * mutable_actual_flange_pose(); +// class KinData : public JSONBase +// { +// public: +// // KinData() = default; +// // KinData(const KinData & other) = default; +// KinData & operator = (const KinData & other); +// void set_actual_joint_pose(const std::vector & +// actual_joint_pose); const std::vector & actual_joint_pose() const; +// std::vector * mutable_actual_joint_pose(); +// void set_actual_joint_speed(const std::vector & +// actual_joint_speed); const std::vector & actual_joint_speed() +// const; std::vector * mutable_actual_joint_speed(); void +// set_actual_joint_acc(const std::vector & actual_joint_acc); const +// std::vector & actual_joint_acc() const; std::vector * +// mutable_actual_joint_acc(); void set_actual_joint_torque(const +// std::vector & actual_joint_torque); const std::vector & +// actual_joint_torque() const; std::vector * +// mutable_actual_joint_torque(); - // protected: - // std::vector actual_joint_pose_; - // std::vector actual_joint_speed_; - // std::vector actual_joint_acc_; - // std::vector actual_joint_torque_; - // std::vector target_joint_pose_; - // std::vector target_joint_speed_; - // std::vector target_joint_acc_; - // std::vector target_joint_torque_; - // posture::CartesianPose actual_tcp_pose_; - // posture::CartesianPose target_tcp_pose_; - // posture::CartesianPose actual_flange_pose_; - // // These methods are used to serialize and deserialize the class. - // // They will not be wrapped in the SDK. - // public: - // virtual bool Deserialize(const rapidjson::Value &obj); - // virtual bool Serialize(rapidjson::Writer *writer) const; - // virtual bool IsNullJSONData() const; - // }; +// void set_target_joint_pose(const std::vector & +// target_joint_pose); const std::vector & target_joint_pose() const; +// std::vector * mutable_target_joint_pose(); +// void set_target_joint_speed(const std::vector & +// target_joint_speed); const std::vector & target_joint_speed() +// const; std::vector * mutable_target_joint_speed(); void +// set_target_joint_acc(const std::vector & target_joint_acc); const +// std::vector & target_joint_acc() const; std::vector * +// mutable_target_joint_acc(); void set_target_joint_torque(const +// std::vector & target_joint_torque); const std::vector & +// target_joint_torque() const; std::vector * +// mutable_target_joint_torque(); - class KinFactor : public JSONBase - { - public: - void set_factor(int factor); - int factor(); - int * mutable_factor(); +// void set_actual_tcp_pose(const posture::CartesianPose & +// actual_tcp_pose); const posture::CartesianPose & actual_tcp_pose() const; +// posture::CartesianPose * mutable_actual_tcp_pose(); +// void set_target_tcp_pose(const posture::CartesianPose & +// target_tcp_pose); const posture::CartesianPose & target_tcp_pose() const; +// posture::CartesianPose * mutable_target_tcp_pose(); +// void set_actual_flange_pose(const posture::CartesianPose & +// actual_flange_pose); const posture::CartesianPose & +// actual_flange_pose() const; posture::CartesianPose * +// mutable_actual_flange_pose(); - protected: - int factor_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +// protected: +// std::vector actual_joint_pose_; +// std::vector actual_joint_speed_; +// std::vector actual_joint_acc_; +// std::vector actual_joint_torque_; +// std::vector target_joint_pose_; +// std::vector target_joint_speed_; +// std::vector target_joint_acc_; +// std::vector target_joint_torque_; +// posture::CartesianPose actual_tcp_pose_; +// posture::CartesianPose target_tcp_pose_; +// posture::CartesianPose actual_flange_pose_; +// // These methods are used to serialize and deserialize the class. +// // They will not be wrapped in the SDK. +// public: +// virtual bool Deserialize(const rapidjson::Value &obj); +// virtual bool Serialize(rapidjson::Writer +// *writer) const; virtual bool IsNullJSONData() const; +// }; + +class KinFactor : public JSONBase { + public: + void set_factor(int factor); + int factor(); + int *mutable_factor(); + + protected: + int factor_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace kinematic +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/led.cc b/sdk/src/protos/led.cc index d951317..092895b 100644 --- a/sdk/src/protos/led.cc +++ b/sdk/src/protos/led.cc @@ -1,384 +1,215 @@ #include #include "led.hh" +namespace lebai { +namespace led { +void LedData::set_mode(LedMode mode) { mode_ = mode; } +LedMode LedData::mode() const { return mode_; } +LedMode *LedData::mutable_mode() { return &mode_; } -namespace lebai -{ - namespace led - { - void LedData::set_mode(LedMode mode) - { - mode_ = mode; +// set_speed +void LedData::set_speed(LedSpeed speed) { speed_ = speed; } +LedSpeed LedData::speed() const { return speed_; } +LedSpeed *LedData::mutable_speed() { return &speed_; } +void LedData::set_colors(const std::vector &colors) { + colors_ = colors; +} +const std::vector &LedData::colors() const { return colors_; } +std::vector *LedData::mutable_colors() { return &colors_; } +// Deserialize +bool LedData::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("mode")) { + std::string mode_str = std::string(obj["mode"].GetString()); + if (mode_str == "HOLD_LED") { + mode_ = HOLD_LED; + } else if (mode_str == "CLOSE_LED") { + mode_ = CLOSE_LED; + } else if (mode_str == "OPEN_LED") { + mode_ = OPEN_LED; + } else if (mode_str == "BREATH") { + mode_ = BREATH; + } else if (mode_str == "FOUR") { + mode_ = FOUR; + } else if (mode_str == "WATER") { + mode_ = WATER; + } else if (mode_str == "BLINK") { + mode_ = BLINK; } - LedMode LedData::mode() const - { - return mode_; - } - LedMode * LedData::mutable_mode() - { - return &mode_; - } - - // set_speed - void LedData::set_speed(LedSpeed speed) - { - speed_ = speed; - } - LedSpeed LedData::speed() const - { - return speed_; - } - LedSpeed * LedData::mutable_speed() - { - return &speed_; - } - void LedData::set_colors(const std::vector & colors) - { - colors_ = colors; - } - const std::vector & LedData::colors() const - { - return colors_; - } - std::vector * LedData::mutable_colors() - { - return &colors_; - } - // Deserialize - bool LedData::Deserialize(const rapidjson::Value& obj) - { - if (obj.HasMember("mode")) - { - std::string mode_str = std::string(obj["mode"].GetString()); - if(mode_str == "HOLD_LED") - { - mode_ = HOLD_LED; - } - else if(mode_str == "CLOSE_LED") - { - mode_ = CLOSE_LED; - } - else if(mode_str == "OPEN_LED") - { - mode_ = OPEN_LED; - } - else if(mode_str == "BREATH") - { - mode_ = BREATH; - } - else if(mode_str == "FOUR") - { - mode_ = FOUR; - } - else if(mode_str == "WATER") - { - mode_ = WATER; - } - else if(mode_str == "BLINK") - { - mode_ = BLINK; - } - } - if (obj.HasMember("speed")) - { - std::string speed_str = std::string(obj["speed"].GetString()); - if(speed_str == "HOLD_LED_SPEED") - { - speed_ = HOLD_LED_SPEED; - } - else if(speed_str == "FAST") - { - speed_ = FAST; - } - else if(speed_str == "NORMAL") - { - speed_ = NORMAL; - } - else if(speed_str == "SLOW") - { - speed_ = SLOW; - } - } - if (obj.HasMember("colors")) - { - const rapidjson::Value& colors = obj["colors"]; - for (rapidjson::SizeType i = 0; i < colors.Size(); i++) - { - std::string color_str = std::string(colors[i].GetString()); - if(color_str == "RED") - { - colors_.push_back(RED); - } - else if(color_str == "GREEN") - { - colors_.push_back(GREEN); - } - else if(color_str == "BLUE") - { - colors_.push_back(BLUE); - } - else if(color_str == "PINK") - { - colors_.push_back(PINK); - } - else if(color_str == "YELLOW") - { - colors_.push_back(YELLOW); - } - else if(color_str == "CYAN") - { - colors_.push_back(CYAN); - } - else if(color_str == "GRAY") - { - colors_.push_back(GRAY); - } - else if(color_str == "BROWN") - { - colors_.push_back(BROWN); - } - else if(color_str == "ORANGE") - { - colors_.push_back(ORANGE); - } - else if(color_str == "GOLD") - { - colors_.push_back(GOLD); - } - else if(color_str == "INDIGO") - { - colors_.push_back(INDIGO); - } - else if(color_str == "LIGHT_SKY_BLUE") - { - colors_.push_back(LIGHT_SKY_BLUE); - } - else if(color_str == "DARK_VIOLET") - { - colors_.push_back(DARK_VIOLET); - } - else if(color_str == "CHOCOLATE") - { - colors_.push_back(CHOCOLATE); - } - else if(color_str == "LIGHT_RED") - { - colors_.push_back(LIGHT_RED); - } - else if(color_str == "WHITE") - { - colors_.push_back(WHITE); - } - } - } - return true; + } + if (obj.HasMember("speed")) { + std::string speed_str = std::string(obj["speed"].GetString()); + if (speed_str == "HOLD_LED_SPEED") { + speed_ = HOLD_LED_SPEED; + } else if (speed_str == "FAST") { + speed_ = FAST; + } else if (speed_str == "NORMAL") { + speed_ = NORMAL; + } else if (speed_str == "SLOW") { + speed_ = SLOW; } - // Serialize - bool LedData::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("mode"); - writer->Int(mode_); - writer->String("speed"); - writer->Int(speed_); - writer->String("colors"); - writer->StartArray(); - for (auto& color : colors_) - { - writer->Int(color); + } + if (obj.HasMember("colors")) { + const rapidjson::Value &colors = obj["colors"]; + for (rapidjson::SizeType i = 0; i < colors.Size(); i++) { + std::string color_str = std::string(colors[i].GetString()); + if (color_str == "RED") { + colors_.push_back(RED); + } else if (color_str == "GREEN") { + colors_.push_back(GREEN); + } else if (color_str == "BLUE") { + colors_.push_back(BLUE); + } else if (color_str == "PINK") { + colors_.push_back(PINK); + } else if (color_str == "YELLOW") { + colors_.push_back(YELLOW); + } else if (color_str == "CYAN") { + colors_.push_back(CYAN); + } else if (color_str == "GRAY") { + colors_.push_back(GRAY); + } else if (color_str == "BROWN") { + colors_.push_back(BROWN); + } else if (color_str == "ORANGE") { + colors_.push_back(ORANGE); + } else if (color_str == "GOLD") { + colors_.push_back(GOLD); + } else if (color_str == "INDIGO") { + colors_.push_back(INDIGO); + } else if (color_str == "LIGHT_SKY_BLUE") { + colors_.push_back(LIGHT_SKY_BLUE); + } else if (color_str == "DARK_VIOLET") { + colors_.push_back(DARK_VIOLET); + } else if (color_str == "CHOCOLATE") { + colors_.push_back(CHOCOLATE); + } else if (color_str == "LIGHT_RED") { + colors_.push_back(LIGHT_RED); + } else if (color_str == "WHITE") { + colors_.push_back(WHITE); } - writer->EndArray(); - writer->EndObject(); - return true; } + } + return true; +} +// Serialize +bool LedData::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("mode"); + writer->Int(mode_); + writer->String("speed"); + writer->Int(speed_); + writer->String("colors"); + writer->StartArray(); + for (auto &color : colors_) { + writer->Int(color); + } + writer->EndArray(); + writer->EndObject(); + return true; +} - bool LedData::IsNullJSONData() const - { - return false; - } +bool LedData::IsNullJSONData() const { return false; } - void VoiceData::set_voice(VoiceKind voice) - { - voice_ = voice; - } +void VoiceData::set_voice(VoiceKind voice) { voice_ = voice; } - VoiceKind VoiceData::voice() const - { - return voice_; - } +VoiceKind VoiceData::voice() const { return voice_; } - VoiceKind * VoiceData::mutable_voice() - { - return &voice_; - } +VoiceKind *VoiceData::mutable_voice() { return &voice_; } - void VoiceData::set_volume(Volume volume) - { - volume_ = volume; - } +void VoiceData::set_volume(Volume volume) { volume_ = volume; } - Volume VoiceData::volume() const - { - return volume_; - } +Volume VoiceData::volume() const { return volume_; } - Volume * VoiceData::mutable_volume() - { - return &volume_; - } +Volume *VoiceData::mutable_volume() { return &volume_; } - bool VoiceData::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("voice")) - { - std::string voice_str = std::string(obj["voice"].GetString()); - if(voice_str == "OFF") - { - voice_ = OFF; - } - else if(voice_str == "BOOTING") - { - voice_ = BOOTING; - } - else if(voice_str == "STOPING") - { - voice_ = STOPING; - } - else if(voice_str == "COLLISION_DETECTED") - { - voice_ = COLLISION_DETECTED; - } - else if(voice_str == "UPGRADE") - { - voice_ = UPGRADE; - } - else if(voice_str == "TEACH_MODE_ON") - { - voice_ = TEACH_MODE_ON; - } - else if(voice_str == "TEACH_MODE_OFF") - { - voice_ = TEACH_MODE_OFF; - } - else if(voice_str == "FINE_TUNNING_ON") - { - voice_ = FINE_TUNNING_ON; - } - else if(voice_str == "FINE_TUNNING_OFF") - { - voice_ = FINE_TUNNING_OFF; - } - else if(voice_str == "FINE_TUNNING_CHANGE") - { - voice_ = FINE_TUNNING_CHANGE; - } - else if(voice_str == "BORING") - { - voice_ = BORING; - } - else if(voice_str == "CUSTOM1") - { - voice_ = CUSTOM1; - } - else if(voice_str == "CUSTOM2") - { - voice_ = CUSTOM2; - } - else if(voice_str == "CUSTOM3") - { - voice_ = CUSTOM3; - } - else if(voice_str == "CUSTOM4") - { - voice_ = CUSTOM4; - } - else if(voice_str == "CUSTOM5") - { - voice_ = CUSTOM5; - } - } - if (obj.HasMember("volume")) - { - std::string volume_str = std::string(obj["volume"].GetString()); - if(volume_str == "MUTE") - { - volume_ = MUTE; - } - else if(volume_str == "LOW") - { - volume_ = LOW; - } - else if(volume_str == "MID") - { - volume_ = MID; - } - else if(volume_str == "HIGH") - { - volume_ = HIGH; - } - } - return true; +bool VoiceData::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("voice")) { + std::string voice_str = std::string(obj["voice"].GetString()); + if (voice_str == "OFF") { + voice_ = OFF; + } else if (voice_str == "BOOTING") { + voice_ = BOOTING; + } else if (voice_str == "STOPING") { + voice_ = STOPING; + } else if (voice_str == "COLLISION_DETECTED") { + voice_ = COLLISION_DETECTED; + } else if (voice_str == "UPGRADE") { + voice_ = UPGRADE; + } else if (voice_str == "TEACH_MODE_ON") { + voice_ = TEACH_MODE_ON; + } else if (voice_str == "TEACH_MODE_OFF") { + voice_ = TEACH_MODE_OFF; + } else if (voice_str == "FINE_TUNNING_ON") { + voice_ = FINE_TUNNING_ON; + } else if (voice_str == "FINE_TUNNING_OFF") { + voice_ = FINE_TUNNING_OFF; + } else if (voice_str == "FINE_TUNNING_CHANGE") { + voice_ = FINE_TUNNING_CHANGE; + } else if (voice_str == "BORING") { + voice_ = BORING; + } else if (voice_str == "CUSTOM1") { + voice_ = CUSTOM1; + } else if (voice_str == "CUSTOM2") { + voice_ = CUSTOM2; + } else if (voice_str == "CUSTOM3") { + voice_ = CUSTOM3; + } else if (voice_str == "CUSTOM4") { + voice_ = CUSTOM4; + } else if (voice_str == "CUSTOM5") { + voice_ = CUSTOM5; } - bool VoiceData::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("voice"); - writer->Int(voice_); - writer->String("volume"); - writer->Int(volume_); - writer->EndObject(); - return true; + } + if (obj.HasMember("volume")) { + std::string volume_str = std::string(obj["volume"].GetString()); + if (volume_str == "MUTE") { + volume_ = MUTE; + } else if (volume_str == "LOW") { + volume_ = LOW; + } else if (volume_str == "MID") { + volume_ = MID; + } else if (volume_str == "HIGH") { + volume_ = HIGH; } + } + return true; +} +bool VoiceData::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("voice"); + writer->Int(voice_); + writer->String("volume"); + writer->Int(volume_); + writer->EndObject(); + return true; +} - bool VoiceData::IsNullJSONData() const - { - return false; - } +bool VoiceData::IsNullJSONData() const { return false; } - void FanData::set_fan(FanMode fan) - { - fan_ = fan; - } - FanMode FanData::fan() const - { - return fan_; - } - FanMode * FanData::mutable_fan() - { - return &fan_; - } +void FanData::set_fan(FanMode fan) { fan_ = fan; } +FanMode FanData::fan() const { return fan_; } +FanMode *FanData::mutable_fan() { return &fan_; } - bool FanData::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("mode")) - { - std::string voice_str = std::string(obj["mode"].GetString()); - if(voice_str == "HOLD_FAN") - { - fan_ = HOLD_FAN; - } - else if(voice_str == "CLOSE_FAN") - { - fan_ = CLOSE_FAN; - } - else if(voice_str == "OPEN_FAN") - { - fan_ = OPEN_FAN; - } - } - return true; - } - bool FanData::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("mode"); - writer->Int(fan_); - writer->EndObject(); - return true; - } - bool FanData::IsNullJSONData() const - { - return false; +bool FanData::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("mode")) { + std::string voice_str = std::string(obj["mode"].GetString()); + if (voice_str == "HOLD_FAN") { + fan_ = HOLD_FAN; + } else if (voice_str == "CLOSE_FAN") { + fan_ = CLOSE_FAN; + } else if (voice_str == "OPEN_FAN") { + fan_ = OPEN_FAN; } } -} \ No newline at end of file + return true; +} +bool FanData::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("mode"); + writer->Int(fan_); + writer->EndObject(); + return true; +} +bool FanData::IsNullJSONData() const { return false; } +} // namespace led +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/led.hh b/sdk/src/protos/led.hh index 712eba0..f41684a 100644 --- a/sdk/src/protos/led.hh +++ b/sdk/src/protos/led.hh @@ -4,146 +4,136 @@ #include #include +namespace lebai { +namespace led { +enum LedMode { + HOLD_LED = 0, + CLOSE_LED = 1, + OPEN_LED = 2, + BREATH = 3, + FOUR = 4, + WATER = 5, + BLINK = 6, +}; +enum LedSpeed { + HOLD_LED_SPEED = 0, + FAST = 1, + NORMAL = 2, + SLOW = 3, +}; +enum LedColor { + RED = 0, + GREEN = 1, + BLUE = 2, + PINK = 3, + YELLOW = 4, + CYAN = 5, + GRAY = 6, + BROWN = 7, + ORANGE = 8, + GOLD = 9, + INDIGO = 10, + LIGHT_SKY_BLUE = 11, + DARK_VIOLET = 12, + CHOCOLATE = 13, + LIGHT_RED = 14, + WHITE = 15, +}; -namespace lebai -{ - namespace led - { - enum LedMode - { - HOLD_LED = 0, - CLOSE_LED = 1, - OPEN_LED = 2, - BREATH = 3, - FOUR = 4, - WATER = 5, - BLINK = 6, - }; - enum LedSpeed - { - HOLD_LED_SPEED = 0, - FAST = 1, - NORMAL = 2, - SLOW = 3, - }; - enum LedColor - { - RED = 0, - GREEN = 1, - BLUE = 2, - PINK = 3, - YELLOW = 4, - CYAN = 5, - GRAY = 6, - BROWN = 7, - ORANGE = 8, - GOLD = 9, - INDIGO = 10, - LIGHT_SKY_BLUE = 11, - DARK_VIOLET = 12, - CHOCOLATE = 13, - LIGHT_RED = 14, - WHITE = 15, - }; +class LedData : public JSONBase { + public: + void set_mode(LedMode mode); + LedMode mode() const; + LedMode *mutable_mode(); - class LedData : public JSONBase - { - public: - void set_mode(LedMode mode); - LedMode mode() const; - LedMode * mutable_mode(); + void set_speed(LedSpeed speed); + LedSpeed speed() const; + LedSpeed *mutable_speed(); - void set_speed(LedSpeed speed); - LedSpeed speed() const; - LedSpeed * mutable_speed(); + void set_colors(const std::vector &colors); + const std::vector &colors() const; + std::vector *mutable_colors(); - void set_colors(const std::vector & colors); - const std::vector & colors() const; - std::vector * mutable_colors(); + protected: + LedMode mode_; + LedSpeed speed_; + std::vector colors_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - protected: - LedMode mode_; - LedSpeed speed_; - std::vector colors_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; +enum VoiceKind { + OFF = 0, + BOOTING = 1, + STOPING = 2, + COLLISION_DETECTED = 3, + UPGRADE = 4, + TEACH_MODE_ON = 5, + TEACH_MODE_OFF = 6, + FINE_TUNNING_ON = 7, + FINE_TUNNING_OFF = 8, + FINE_TUNNING_CHANGE = 9, + BORING = 10, + CUSTOM1 = 11, + CUSTOM2 = 12, + CUSTOM3 = 13, + CUSTOM4 = 14, + CUSTOM5 = 15, +}; +enum Volume { + MUTE = 0, + LOW = 1, + MID = 2, + HIGH = 3, +}; +class VoiceData : public JSONBase { + public: + void set_voice(VoiceKind voice); + VoiceKind voice() const; + VoiceKind *mutable_voice(); - enum VoiceKind - { - OFF = 0, - BOOTING = 1, - STOPING = 2, - COLLISION_DETECTED = 3, - UPGRADE = 4, - TEACH_MODE_ON = 5, - TEACH_MODE_OFF = 6, - FINE_TUNNING_ON = 7, - FINE_TUNNING_OFF = 8, - FINE_TUNNING_CHANGE = 9, - BORING = 10, - CUSTOM1 = 11, - CUSTOM2 = 12, - CUSTOM3 = 13, - CUSTOM4 = 14, - CUSTOM5 = 15, - }; + void set_volume(Volume volume); + Volume volume() const; + Volume *mutable_volume(); - enum Volume - { - MUTE = 0, - LOW = 1, - MID = 2, - HIGH = 3, - }; - class VoiceData : public JSONBase - { - public: - void set_voice(VoiceKind voice); - VoiceKind voice() const; - VoiceKind * mutable_voice(); + protected: + VoiceKind voice_; + Volume volume_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - void set_volume(Volume volume); - Volume volume() const; - Volume * mutable_volume(); +enum FanMode { + HOLD_FAN = 0, + CLOSE_FAN = 1, + OPEN_FAN = 2, +}; +class FanData : public JSONBase { + public: + void set_fan(FanMode fan); + FanMode fan() const; + FanMode *mutable_fan(); - protected: - VoiceKind voice_; - Volume volume_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - enum FanMode - { - HOLD_FAN = 0, - CLOSE_FAN = 1, - OPEN_FAN = 2, - }; - class FanData : public JSONBase - { - public: - void set_fan(FanMode fan); - FanMode fan() const; - FanMode * mutable_fan(); - - protected: - FanMode fan_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file + protected: + FanMode fan_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace led +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/modbus.cc b/sdk/src/protos/modbus.cc index e6ed9d9..3b3054c 100644 --- a/sdk/src/protos/modbus.cc +++ b/sdk/src/protos/modbus.cc @@ -1,567 +1,339 @@ #include #include "modbus.hh" +namespace lebai { +namespace modbus { +void SetCoilsRequest::set_device(std::string device) { device_ = device; } +std::string SetCoilsRequest::device() const { return device_; } +std::string *SetCoilsRequest::mutable_device() { return &device_; } -namespace lebai -{ - namespace modbus{ - void SetCoilsRequest::set_device(std::string device) - { - device_ = device; - } - std::string SetCoilsRequest::device() const - { - return device_; - } - std::string *SetCoilsRequest::mutable_device() - { - return &device_; - } +void SetCoilsRequest::set_pin(std::string pin) { pin_ = pin; } +std::string SetCoilsRequest::pin() const { return pin_; } +std::string *SetCoilsRequest::mutable_pin() { return &pin_; } - void SetCoilsRequest::set_pin(std::string pin) - { - pin_ = pin; - } - std::string SetCoilsRequest::pin() const - { - return pin_; - } - std::string *SetCoilsRequest::mutable_pin() - { - return &pin_; - } +void SetCoilsRequest::set_values(std::vector values) { values = values_; } +std::vector SetCoilsRequest::values() const { return values_; } +std::vector *SetCoilsRequest::mutable_values() { return &values_; } - void SetCoilsRequest::set_values(std::vector values) - { - values = values_; - } - std::vector SetCoilsRequest::values() const - { - return values_; - } - std::vector *SetCoilsRequest::mutable_values() - { - return &values_; - } - - bool SetCoilsRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if(obj.HasMember("pin")) - { - std::string pin_str = std::string(obj["pin"].GetString()); - pin_ = pin_str; - } - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - bool value_bool = bool(i->GetBool()); - values.push_back(value_bool); - } - values_ = values; - } - return true; - } - bool SetCoilsRequest::Serialize(rapidjson::Writer *writer) const - { - - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("pin"); - writer->String(pin_.c_str()); - writer->Key("values"); - writer->StartArray(); - for(auto i:values_) - { - writer->Bool(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool SetCoilsRequest::IsNullJSONData() const - { - return values_.size() == 0; - } - void SetCoilRequest::set_device(std::string device) - { - device_ = device; - } - std::string SetCoilRequest::device() const - { - return device_; - } - std::string *SetCoilRequest::mutable_device() - { - return &device_; - } - - void SetCoilRequest::set_pin(std::string pin) - { - pin_ = pin; - } - std::string SetCoilRequest::pin() const - { - return pin_; - } - std::string *SetCoilRequest::mutable_pin() - { - return &pin_; - } - - void SetCoilRequest::set_value(bool values) - { - values = value_; - } - bool SetCoilRequest::value() const - { - return value_; - } - bool *SetCoilRequest::mutable_value() - { - return &value_; - } - - bool SetCoilRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if (obj.HasMember("pin")) - { - std::string pin_str = std::string(obj["pin"].GetString()); - pin_ = pin_str; - } - if (obj.HasMember("values")) - { - bool values = bool(obj["values"].GetBool()); - value_ = values; - } - return true; - } - bool SetCoilRequest::Serialize(rapidjson::Writer *writer) const - { - - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("pin"); - writer->String(pin_.c_str()); - writer->Key("value"); - writer->Bool(value_); - writer->EndObject(); - return true; - } - bool SetCoilRequest::IsNullJSONData() const - { - return false; - } - void GetCoilsRequest::set_device(std::string device) - { - device_ = device; - } - std::string GetCoilsRequest::device() const - { - return device_; - } - std::string *GetCoilsRequest::mutable_device() - { - return &device_; - } - - void GetCoilsRequest::set_pin(std::string pin) - { - pin_ = pin; - } - std::string GetCoilsRequest::pin() const - { - return pin_; - } - std::string *GetCoilsRequest::mutable_pin() - { - return &pin_; - } +bool SetCoilsRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("pin")) { + std::string pin_str = std::string(obj["pin"].GetString()); + pin_ = pin_str; + } + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + bool value_bool = bool(i->GetBool()); + values.push_back(value_bool); + } + values_ = values; + } + return true; +} +bool SetCoilsRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("pin"); + writer->String(pin_.c_str()); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Bool(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool SetCoilsRequest::IsNullJSONData() const { return values_.size() == 0; } +void SetCoilRequest::set_device(std::string device) { device_ = device; } +std::string SetCoilRequest::device() const { return device_; } +std::string *SetCoilRequest::mutable_device() { return &device_; } - void GetCoilsRequest::set_count(unsigned int count) - { - count = count_; - } - unsigned int GetCoilsRequest::count() const - { - return count_; - } - unsigned int *GetCoilsRequest::mutable_count() - { - return &count_; - } +void SetCoilRequest::set_pin(std::string pin) { pin_ = pin; } +std::string SetCoilRequest::pin() const { return pin_; } +std::string *SetCoilRequest::mutable_pin() { return &pin_; } - bool GetCoilsRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if (obj.HasMember("pin")) - { - std::string pin_str = std::string(obj["pin"].GetString()); - pin_ = pin_str; - } - if (obj.HasMember("count")) - { - bool count = bool(obj["count"].GetUint()); - count_ = count; - } - return true; - } - bool GetCoilsRequest::Serialize(rapidjson::Writer *writer) const - { +void SetCoilRequest::set_value(bool values) { values = value_; } +bool SetCoilRequest::value() const { return value_; } +bool *SetCoilRequest::mutable_value() { return &value_; } - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("pin"); - writer->String(pin_.c_str()); - writer->Key("count"); - writer->Uint(count_); - writer->EndObject(); - return true; - } - bool GetCoilsRequest::IsNullJSONData() const - { - return false; - } +bool SetCoilRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("pin")) { + std::string pin_str = std::string(obj["pin"].GetString()); + pin_ = pin_str; + } + if (obj.HasMember("values")) { + bool values = bool(obj["values"].GetBool()); + value_ = values; + } + return true; +} +bool SetCoilRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("pin"); + writer->String(pin_.c_str()); + writer->Key("value"); + writer->Bool(value_); + writer->EndObject(); + return true; +} +bool SetCoilRequest::IsNullJSONData() const { return false; } +void GetCoilsRequest::set_device(std::string device) { device_ = device; } +std::string GetCoilsRequest::device() const { return device_; } +std::string *GetCoilsRequest::mutable_device() { return &device_; } - void GetCoilsResponse::set_values(std::vector values) - { - values_ = values; - } - std::vector GetCoilsResponse::values() const - { - return values_; - } - std::vector *GetCoilsResponse::mutable_values() - { - return &values_; - } - bool GetCoilsResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back(bool(i->GetBool())); - } - values_ = values; - } - return true; - } - bool GetCoilsResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("values"); - writer->StartArray(); - for(auto i:values_) - { - writer->Bool(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool GetCoilsResponse::IsNullJSONData() const - { - return values_.size() == 0; - } +void GetCoilsRequest::set_pin(std::string pin) { pin_ = pin; } +std::string GetCoilsRequest::pin() const { return pin_; } +std::string *GetCoilsRequest::mutable_pin() { return &pin_; } - void SetRegistersRequest::set_device(std::string device) - { - device_ = device; - } - std::string SetRegistersRequest::device() const - { - return device_; - } - std::string *SetRegistersRequest::mutable_device() - { - return &device_; - } +void GetCoilsRequest::set_count(unsigned int count) { count = count_; } +unsigned int GetCoilsRequest::count() const { return count_; } +unsigned int *GetCoilsRequest::mutable_count() { return &count_; } - void SetRegistersRequest::set_pin(std::string pin) - { - pin_ = pin; - } - std::string SetRegistersRequest::pin() const - { - return pin_; - } - std::string *SetRegistersRequest::mutable_pin() - { - return &pin_; - } +bool GetCoilsRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("pin")) { + std::string pin_str = std::string(obj["pin"].GetString()); + pin_ = pin_str; + } + if (obj.HasMember("count")) { + bool count = bool(obj["count"].GetUint()); + count_ = count; + } + return true; +} +bool GetCoilsRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("pin"); + writer->String(pin_.c_str()); + writer->Key("count"); + writer->Uint(count_); + writer->EndObject(); + return true; +} +bool GetCoilsRequest::IsNullJSONData() const { return false; } - void SetRegistersRequest::set_values(std::vector values) - { - values = values_; - } - std::vector SetRegistersRequest::values() const - { - return values_; - } - std::vector *SetRegistersRequest::mutable_values() - { - return &values_; - } +void GetCoilsResponse::set_values(std::vector values) { + values_ = values; +} +std::vector GetCoilsResponse::values() const { return values_; } +std::vector *GetCoilsResponse::mutable_values() { return &values_; } +bool GetCoilsResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back(bool(i->GetBool())); + } + values_ = values; + } + return true; +} +bool GetCoilsResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Bool(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool GetCoilsResponse::IsNullJSONData() const { return values_.size() == 0; } - bool SetRegistersRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if (obj.HasMember("pin")) - { - std::string pin_str = std::string(obj["pin"].GetString()); - pin_ = pin_str; - } - if (obj.HasMember("values")) - { - std::vector values; - for (auto i = obj["values"].GetArray().Begin(); i != obj["values"].GetArray().End(); i++) - { - unsigned int value_uint = (unsigned int)(i->GetUint()); - values.push_back(value_uint); - } - values_ = values; - } - return true; - } - bool SetRegistersRequest::Serialize(rapidjson::Writer *writer) const - { +void SetRegistersRequest::set_device(std::string device) { device_ = device; } +std::string SetRegistersRequest::device() const { return device_; } +std::string *SetRegistersRequest::mutable_device() { return &device_; } - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("pin"); - writer->String(pin_.c_str()); - writer->Key("values"); - writer->StartArray(); - for (auto i : values_) - { - writer->Bool(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool SetRegistersRequest::IsNullJSONData() const - { - return values_.size() == 0; - } - void SetRegisterRequest::set_device(std::string device) - { - device_ = device; - } - std::string SetRegisterRequest::device() const - { - return device_; - } - std::string *SetRegisterRequest::mutable_device() - { - return &device_; - } +void SetRegistersRequest::set_pin(std::string pin) { pin_ = pin; } +std::string SetRegistersRequest::pin() const { return pin_; } +std::string *SetRegistersRequest::mutable_pin() { return &pin_; } - void SetRegisterRequest::set_pin(std::string pin) - { - pin_ = pin; - } - std::string SetRegisterRequest::pin() const - { - return pin_; - } - std::string *SetRegisterRequest::mutable_pin() - { - return &pin_; - } +void SetRegistersRequest::set_values(std::vector values) { + values = values_; +} +std::vector SetRegistersRequest::values() const { + return values_; +} +std::vector *SetRegistersRequest::mutable_values() { + return &values_; +} - void SetRegisterRequest::set_value(unsigned int values) - { - values = value_; - } - unsigned int SetRegisterRequest::value() const - { - return value_; - } - unsigned int *SetRegisterRequest::mutable_value() - { - return &value_; - } +bool SetRegistersRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("pin")) { + std::string pin_str = std::string(obj["pin"].GetString()); + pin_ = pin_str; + } + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + unsigned int value_uint = (unsigned int)(i->GetUint()); + values.push_back(value_uint); + } + values_ = values; + } + return true; +} +bool SetRegistersRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("pin"); + writer->String(pin_.c_str()); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Bool(i); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool SetRegistersRequest::IsNullJSONData() const { return values_.size() == 0; } +void SetRegisterRequest::set_device(std::string device) { device_ = device; } +std::string SetRegisterRequest::device() const { return device_; } +std::string *SetRegisterRequest::mutable_device() { return &device_; } - bool SetRegisterRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if (obj.HasMember("pin")) - { - std::string pin_str = std::string(obj["pin"].GetString()); - pin_ = pin_str; - } - if (obj.HasMember("values")) - { - unsigned int values = (unsigned int)(obj["values"].GetUint()); - value_ = values; - } - return true; - } - bool SetRegisterRequest::Serialize(rapidjson::Writer *writer) const - { +void SetRegisterRequest::set_pin(std::string pin) { pin_ = pin; } +std::string SetRegisterRequest::pin() const { return pin_; } +std::string *SetRegisterRequest::mutable_pin() { return &pin_; } - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("pin"); - writer->String(pin_.c_str()); - writer->Key("value"); - writer->Bool(value_); - writer->EndObject(); - return true; - } - bool SetRegisterRequest::IsNullJSONData() const - { - return false; - } +void SetRegisterRequest::set_value(unsigned int values) { values = value_; } +unsigned int SetRegisterRequest::value() const { return value_; } +unsigned int *SetRegisterRequest::mutable_value() { return &value_; } - void GetRegistersRequest::set_device(std::string device) - { - device_ = device; - } - std::string GetRegistersRequest::device() const - { - return device_; - } - std::string *GetRegistersRequest::mutable_device() - { - return &device_; - } +bool SetRegisterRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("pin")) { + std::string pin_str = std::string(obj["pin"].GetString()); + pin_ = pin_str; + } + if (obj.HasMember("values")) { + unsigned int values = (unsigned int)(obj["values"].GetUint()); + value_ = values; + } + return true; +} +bool SetRegisterRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("pin"); + writer->String(pin_.c_str()); + writer->Key("value"); + writer->Bool(value_); + writer->EndObject(); + return true; +} +bool SetRegisterRequest::IsNullJSONData() const { return false; } - void GetRegistersRequest::set_pin(std::string pin) - { - pin_ = pin; - } - std::string GetRegistersRequest::pin() const - { - return pin_; - } - std::string *GetRegistersRequest::mutable_pin() - { - return &pin_; - } +void GetRegistersRequest::set_device(std::string device) { device_ = device; } +std::string GetRegistersRequest::device() const { return device_; } +std::string *GetRegistersRequest::mutable_device() { return &device_; } - void GetRegistersRequest::set_count(unsigned int count) - { - count = count_; - } - unsigned int GetRegistersRequest::count() const - { - return count_; - } - unsigned int *GetRegistersRequest::mutable_count() - { - return &count_; - } +void GetRegistersRequest::set_pin(std::string pin) { pin_ = pin; } +std::string GetRegistersRequest::pin() const { return pin_; } +std::string *GetRegistersRequest::mutable_pin() { return &pin_; } - bool GetRegistersRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if (obj.HasMember("pin")) - { - std::string pin_str = std::string(obj["pin"].GetString()); - pin_ = pin_str; - } - if (obj.HasMember("count")) - { - bool count = bool(obj["count"].GetUint()); - count_ = count; - } - return true; - } - bool GetRegistersRequest::Serialize(rapidjson::Writer *writer) const - { +void GetRegistersRequest::set_count(unsigned int count) { count = count_; } +unsigned int GetRegistersRequest::count() const { return count_; } +unsigned int *GetRegistersRequest::mutable_count() { return &count_; } - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("pin"); - writer->String(pin_.c_str()); - writer->Key("count"); - writer->Uint(count_); - writer->EndObject(); - return true; - } - bool GetRegistersRequest::IsNullJSONData() const - { - return false; - } +bool GetRegistersRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("pin")) { + std::string pin_str = std::string(obj["pin"].GetString()); + pin_ = pin_str; + } + if (obj.HasMember("count")) { + bool count = bool(obj["count"].GetUint()); + count_ = count; + } + return true; +} +bool GetRegistersRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("pin"); + writer->String(pin_.c_str()); + writer->Key("count"); + writer->Uint(count_); + writer->EndObject(); + return true; +} +bool GetRegistersRequest::IsNullJSONData() const { return false; } - void GetRegistersResponse::set_values(std::vector values) - { - values_ = values; - } - std::vector GetRegistersResponse::values() const - { - return values_; - } - std::vector *GetRegistersResponse::mutable_values() - { - return &values_; - } - bool GetRegistersResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("values")) - { - std::vector values; - for(auto i = obj["values"].GetArray().Begin();i != obj["values"].GetArray().End();i++) - { - values.push_back((unsigned int)(i->GetUint())); - } - values_ = values; - } - return true; - } - bool GetRegistersResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("values"); - writer->StartArray(); - for(auto i:values_) - { - writer->Uint(i); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool GetRegistersResponse::IsNullJSONData() const - { - return values_.size() == 0; - } +void GetRegistersResponse::set_values(std::vector values) { + values_ = values; +} +std::vector GetRegistersResponse::values() const { + return values_; +} +std::vector *GetRegistersResponse::mutable_values() { + return &values_; +} +bool GetRegistersResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("values")) { + std::vector values; + for (auto i = obj["values"].GetArray().Begin(); + i != obj["values"].GetArray().End(); i++) { + values.push_back((unsigned int)(i->GetUint())); + } + values_ = values; + } + return true; +} +bool GetRegistersResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("values"); + writer->StartArray(); + for (auto i : values_) { + writer->Uint(i); } -} \ No newline at end of file + writer->EndArray(); + writer->EndObject(); + return true; +} +bool GetRegistersResponse::IsNullJSONData() const { + return values_.size() == 0; +} +} // namespace modbus +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/modbus.hh b/sdk/src/protos/modbus.hh index 9617615..4b79485 100644 --- a/sdk/src/protos/modbus.hh +++ b/sdk/src/protos/modbus.hh @@ -4,206 +4,202 @@ #include #include - -namespace lebai -{ - namespace modbus - { - class SetCoilRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_pin(std::string pin); - std::string pin() const; - std::string *mutable_pin(); - - void set_value(bool values); - bool value() const; - bool *mutable_value(); - - protected: - std::string device_; - std::string pin_; - bool value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetCoilsRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_pin(std::string pin); - std::string pin() const; - std::string *mutable_pin(); - - void set_values(std::vector values); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::string device_; - std::string pin_; - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetCoilsRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_pin(std::string pin); - std::string pin() const; - std::string *mutable_pin(); - - void set_count(unsigned int count); - unsigned int count() const; - unsigned int *mutable_count(); - - protected: - std::string device_; - std::string pin_; - unsigned int count_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetCoilsResponse : public JSONBase - { - public: - void set_values(std::vector values); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - - class SetRegisterRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_pin(std::string pin); - std::string pin() const; - std::string *mutable_pin(); - - void set_value(unsigned int values); - unsigned int value() const; - unsigned int *mutable_value(); - - protected: - std::string device_; - std::string pin_; - unsigned int value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class SetRegistersRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_pin(std::string pin); - std::string pin() const; - std::string *mutable_pin(); - - void set_values(std::vector values); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::string device_; - std::string pin_; - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetRegistersRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_pin(std::string pin); - std::string pin() const; - std::string *mutable_pin(); - - void set_count(unsigned int count); - unsigned int count() const; - unsigned int *mutable_count(); - - protected: - std::string device_; - std::string pin_; - unsigned int count_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - class GetRegistersResponse : public JSONBase - { - public: - void set_values(std::vector values); - std::vector values() const; - std::vector *mutable_values(); - - protected: - std::vector values_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +namespace lebai { +namespace modbus { +class SetCoilRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_pin(std::string pin); + std::string pin() const; + std::string *mutable_pin(); + + void set_value(bool values); + bool value() const; + bool *mutable_value(); + + protected: + std::string device_; + std::string pin_; + bool value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetCoilsRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_pin(std::string pin); + std::string pin() const; + std::string *mutable_pin(); + + void set_values(std::vector values); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::string device_; + std::string pin_; + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetCoilsRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_pin(std::string pin); + std::string pin() const; + std::string *mutable_pin(); + + void set_count(unsigned int count); + unsigned int count() const; + unsigned int *mutable_count(); + + protected: + std::string device_; + std::string pin_; + unsigned int count_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetCoilsResponse : public JSONBase { + public: + void set_values(std::vector values); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetRegisterRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_pin(std::string pin); + std::string pin() const; + std::string *mutable_pin(); + + void set_value(unsigned int values); + unsigned int value() const; + unsigned int *mutable_value(); + + protected: + std::string device_; + std::string pin_; + unsigned int value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class SetRegistersRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_pin(std::string pin); + std::string pin() const; + std::string *mutable_pin(); + + void set_values(std::vector values); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::string device_; + std::string pin_; + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetRegistersRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_pin(std::string pin); + std::string pin() const; + std::string *mutable_pin(); + + void set_count(unsigned int count); + unsigned int count() const; + unsigned int *mutable_count(); + + protected: + std::string device_; + std::string pin_; + unsigned int count_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +class GetRegistersResponse : public JSONBase { + public: + void set_values(std::vector values); + std::vector values() const; + std::vector *mutable_values(); + + protected: + std::vector values_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace modbus +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/motion.cc b/sdk/src/protos/motion.cc index 0e41b4a..969e475 100644 --- a/sdk/src/protos/motion.cc +++ b/sdk/src/protos/motion.cc @@ -2,901 +2,582 @@ #include #include "motion.hh" -namespace lebai -{ - namespace motion { - // MoveParam begin - MoveParam::MoveParam() - { - - } - MoveParam::MoveParam(const MoveParam & other) - { - *this = other; - // if(other.v_) - // { - // v_ = std::make_unique(other.v_); - // } - // if(other.a_) - // { - // a_ = std::make_unique(other.a_); - // } - // if(other.t_) - // { - // t_ = std::make_unique(other.t_); - // } - // if(other.r_) - // { - // r_ = std::make_unique(other.r_); - // } - } - MoveParam & MoveParam::operator = (const MoveParam & other) - { - velocity_.reset(); - if(other.velocity_) - { - velocity_ = std::make_unique(*other.velocity_); - } - acc_.reset(); - if(other.acc_) - { - acc_ = std::make_unique(*other.acc_); - } - time_.reset(); - if(other.time_) - { - time_ = std::make_unique(*other.time_); - } - radius_.reset(); - if(other.radius_) - { - radius_ = std::make_unique(*other.radius_); - } - return *this; - } - void MoveParam::set_velocity(double v) - { - velocity_ = std::make_unique(v); - } - // double v() const; - double * MoveParam::velocity() const - { - return velocity_.get(); - } - double * MoveParam::mutable_velocity() - { - if(velocity_ == nullptr) - { +namespace lebai { +namespace motion { +// MoveParam begin +MoveParam::MoveParam() {} +MoveParam::MoveParam(const MoveParam& other) { + *this = other; + // if(other.v_) + // { + // v_ = std::make_unique(other.v_); + // } + // if(other.a_) + // { + // a_ = std::make_unique(other.a_); + // } + // if(other.t_) + // { + // t_ = std::make_unique(other.t_); + // } + // if(other.r_) + // { + // r_ = std::make_unique(other.r_); + // } +} +MoveParam& MoveParam::operator=(const MoveParam& other) { + velocity_.reset(); + if (other.velocity_) { + velocity_ = std::make_unique(*other.velocity_); + } + acc_.reset(); + if (other.acc_) { + acc_ = std::make_unique(*other.acc_); + } + time_.reset(); + if (other.time_) { + time_ = std::make_unique(*other.time_); + } + radius_.reset(); + if (other.radius_) { + radius_ = std::make_unique(*other.radius_); + } + return *this; +} +void MoveParam::set_velocity(double v) { + velocity_ = std::make_unique(v); +} +// double v() const; +double* MoveParam::velocity() const { return velocity_.get(); } +double* MoveParam::mutable_velocity() { + if (velocity_ == nullptr) { + velocity_ = std::make_unique(); + } + return velocity_.get(); +} +// void set_a(double); +void MoveParam::set_acc(double a) { acc_ = std::make_unique(a); } +// double a() const; +double* MoveParam::acc() const { return acc_.get(); } +double* MoveParam::mutable_acc() { + if (acc_ == nullptr) { + acc_ = std::make_unique(); + } + return acc_.get(); +} +// void set_t(double); +void MoveParam::set_time(double time) { + time_ = std::make_unique(time); +} +// double t() const; +double* MoveParam::t() const { return time_.get(); } +double* MoveParam::mutable_time() { + if (time_ == nullptr) { + time_ = std::make_unique(); + } + return time_.get(); +} +// void set_r(double); +void MoveParam::set_radius(double r) { radius_ = std::make_unique(r); } +// double r() const; +double* MoveParam::radius() const { return radius_.get(); } +// double & mutable_r(); +double* MoveParam::mutable_radius() { + if (radius_ == nullptr) { + radius_ = std::make_unique(); + } + return radius_.get(); +} + +bool MoveParam::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("velocity")) { + if (!velocity_) { velocity_ = std::make_unique(); + *velocity_ = obj["velocity"].GetDouble(); } - return velocity_.get(); - } - // void set_a(double); - void MoveParam::set_acc(double a) - { - acc_ = std::make_unique(a); - } - // double a() const; - double * MoveParam::acc() const - { - return acc_.get(); - } - double * MoveParam::mutable_acc() - { - if(acc_ == nullptr) - { + } else { + velocity_.reset(); + } + if (obj.HasMember("acc")) { + if (!acc_) { acc_ = std::make_unique(); + *acc_ = obj["acc"].GetDouble(); } - return acc_.get(); - } - // void set_t(double); - void MoveParam::set_time(double time) - { - time_ = std::make_unique(time); - } - // double t() const; - double * MoveParam::t() const - { - return time_.get(); - } - double * MoveParam::mutable_time() - { - if(time_ == nullptr) - { + } else { + acc_.reset(); + } + if (obj.HasMember("time")) { + if (!time_) { time_ = std::make_unique(); + *time_ = obj["time"].GetDouble(); } - return time_.get(); - } - // void set_r(double); - void MoveParam::set_radius(double r) - { - radius_ = std::make_unique(r); - } - // double r() const; - double * MoveParam::radius() const - { - return radius_.get(); - } - // double & mutable_r(); - double * MoveParam::mutable_radius() - { - if(radius_ == nullptr) - { + } else { + time_.reset(); + } + if (obj.HasMember("radius")) { + if (!radius_) { radius_ = std::make_unique(); + *radius_ = obj["radius"].GetDouble(); } - return radius_.get(); - } - - bool MoveParam::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("velocity")) - { - if(!velocity_) - { - velocity_ = std::make_unique(); - *velocity_ = obj["velocity"].GetDouble(); - } - } - else - { - velocity_.reset(); - } - if(obj.HasMember("acc")) - { - if(!acc_) - { - acc_ = std::make_unique(); - *acc_ = obj["acc"].GetDouble(); - } - } - else - { - acc_.reset(); - } - if(obj.HasMember("time")) - { - if(!time_) - { - time_ = std::make_unique(); - *time_ = obj["time"].GetDouble(); - } - } - else - { - time_.reset(); - } - if(obj.HasMember("radius")) - { - if(!radius_) - { - radius_ = std::make_unique(); - *radius_ = obj["radius"].GetDouble(); - } - } - else - { - radius_.reset(); - } - return true; + } else { + radius_.reset(); } + return true; +} - bool MoveParam::Serialize(rapidjson::Writer* writer) const - { - - writer->StartObject(); - if(velocity_) - { - writer->String("velocity"); - writer->Double(*velocity_); - } - if(acc_) - { - writer->String("acc"); - writer->Double(*acc_); - } - if(time_) - { - writer->String("time"); - writer->Double(*time_); - } - if(radius_) - { - writer->String("radius"); - writer->Double(*radius_); - } - writer->EndObject(); - return true; - } - bool MoveParam::IsNullJSONData() const - { - if(velocity_ || acc_ || time_ || radius_) - { - return false; - } - return true; +bool MoveParam::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + if (velocity_) { + writer->String("velocity"); + writer->Double(*velocity_); + } + if (acc_) { + writer->String("acc"); + writer->Double(*acc_); + } + if (time_) { + writer->String("time"); + writer->Double(*time_); + } + if (radius_) { + writer->String("radius"); + writer->Double(*radius_); + } + writer->EndObject(); + return true; +} +bool MoveParam::IsNullJSONData() const { + if (velocity_ || acc_ || time_ || radius_) { + return false; } - // MoveParam end + return true; +} +// MoveParam end +// MoveRequest begin +void MoveRequest::set_param(const MoveParam& param) { param_ = param; } +const MoveParam& MoveRequest::param() const { return param_; } +MoveParam* MoveRequest::mutable_param() { return ¶m_; } - // MoveRequest begin - void MoveRequest::set_param(const MoveParam & param) - { - param_ = param; - } - const MoveParam & MoveRequest::param() const - { - return param_; - } - MoveParam * MoveRequest::mutable_param() - { - return ¶m_; - } +void MoveRequest::set_pose(const posture::Pose& pose) { pose_ = pose; } +const posture::Pose& MoveRequest::pose() const { return pose_; } +posture::Pose* MoveRequest::mutable_pose() { return &pose_; } - void MoveRequest::set_pose(const posture::Pose & pose) - { - pose_ = pose; - } - const posture::Pose & MoveRequest::pose() const - { - return pose_; - } - posture::Pose * MoveRequest::mutable_pose() - { - return &pose_; - } - - bool MoveRequest::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("param")) - { - param_.Deserialize(obj["param"]); - } - if(obj.HasMember("pose")) - { - pose_.Deserialize(obj["pose"]); - } - return true; +bool MoveRequest::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("param")) { + param_.Deserialize(obj["param"]); } + if (obj.HasMember("pose")) { + pose_.Deserialize(obj["pose"]); + } + return true; +} - bool MoveRequest::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - if(!param_.IsNullJSONData()) - { - writer->String("param"); - param_.Serialize(writer); - } - if(!pose_.IsNullJSONData()) - { - writer->String("pose"); - pose_.Serialize(writer); - } - writer->EndObject(); +bool MoveRequest::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + if (!param_.IsNullJSONData()) { + writer->String("param"); + param_.Serialize(writer); + } + if (!pose_.IsNullJSONData()) { + writer->String("pose"); + pose_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool MoveRequest::IsNullJSONData() const { + if (param_.IsNullJSONData() && pose_.IsNullJSONData()) { return true; } - bool MoveRequest::IsNullJSONData() const - { - if(param_.IsNullJSONData() && pose_.IsNullJSONData()) - { - return true; - } - return false; - } - // MoveRequest end + return false; +} +// MoveRequest end - // pose_via_ - void MovecRequest::set_pose_via(const posture::Pose & pose) - { - pose_via_ = pose; - } - const posture::Pose & MovecRequest::pose_via() const - { - return pose_via_; - } - posture::Pose * MovecRequest::mutable_pose_via() - { - return &pose_via_; - } - // pose_ - void MovecRequest::set_pose(const posture::Pose & pose) - { - pose_ = pose; - } - const posture::Pose & MovecRequest::pose() const - { - return pose_; - } - posture::Pose * MovecRequest::mutable_pose() - { - return &pose_; - } - // param_ - void MovecRequest::set_param(const MoveParam & param) - { - param_ = param; - } - const MoveParam & MovecRequest::param() const - { - return param_; - } - MoveParam * MovecRequest::mutable_param() - { - return ¶m_; - } - // rad_ - void MovecRequest::set_rad(double rad) - { - rad_ = rad; - } - double MovecRequest::rad() const - { - return rad_; - } - double * MovecRequest::mutable_rad() - { - return &rad_; - } - bool MovecRequest::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("pose_via")) - { - pose_via_.Deserialize(obj["pose_via"]); - } - if(obj.HasMember("pose")) - { - pose_.Deserialize(obj["pose"]); - } - if(obj.HasMember("param")) - { - param_.Deserialize(obj["param"]); - } - if(obj.HasMember("rad")) - { - rad_ = obj["rad"].GetDouble(); - } +// pose_via_ +void MovecRequest::set_pose_via(const posture::Pose& pose) { pose_via_ = pose; } +const posture::Pose& MovecRequest::pose_via() const { return pose_via_; } +posture::Pose* MovecRequest::mutable_pose_via() { return &pose_via_; } +// pose_ +void MovecRequest::set_pose(const posture::Pose& pose) { pose_ = pose; } +const posture::Pose& MovecRequest::pose() const { return pose_; } +posture::Pose* MovecRequest::mutable_pose() { return &pose_; } +// param_ +void MovecRequest::set_param(const MoveParam& param) { param_ = param; } +const MoveParam& MovecRequest::param() const { return param_; } +MoveParam* MovecRequest::mutable_param() { return ¶m_; } +// rad_ +void MovecRequest::set_rad(double rad) { rad_ = rad; } +double MovecRequest::rad() const { return rad_; } +double* MovecRequest::mutable_rad() { return &rad_; } +bool MovecRequest::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("pose_via")) { + pose_via_.Deserialize(obj["pose_via"]); + } + if (obj.HasMember("pose")) { + pose_.Deserialize(obj["pose"]); + } + if (obj.HasMember("param")) { + param_.Deserialize(obj["param"]); + } + if (obj.HasMember("rad")) { + rad_ = obj["rad"].GetDouble(); + } + return true; +} +bool MovecRequest::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + if (!pose_via_.IsNullJSONData()) { + writer->String("pose_via"); + pose_via_.Serialize(writer); + } + if (!pose_.IsNullJSONData()) { + writer->String("pose"); + pose_.Serialize(writer); + } + if (!param_.IsNullJSONData()) { + writer->String("param"); + param_.Serialize(writer); + } + writer->String("rad"); + writer->Double(rad_); + writer->EndObject(); + return true; +} +bool MovecRequest::IsNullJSONData() const { + if (pose_via_.IsNullJSONData() && pose_.IsNullJSONData() && + param_.IsNullJSONData() && std::abs(rad_) < 1e-6) { return true; } - bool MovecRequest::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - if(!pose_via_.IsNullJSONData()) - { - writer->String("pose_via"); - pose_via_.Serialize(writer); - } - if(!pose_.IsNullJSONData()) - { - writer->String("pose"); - pose_.Serialize(writer); - } - if(!param_.IsNullJSONData()) - { - writer->String("param"); - param_.Serialize(writer); - } - writer->String("rad"); - writer->Double(rad_); - writer->EndObject(); - return true; - } - bool MovecRequest::IsNullJSONData() const - { - if(pose_via_.IsNullJSONData() && pose_.IsNullJSONData() && param_.IsNullJSONData() && std::abs(rad_) < 1e-6) - { - return true; - } - { - return true; - } - return false; - } + { return true; } + return false; +} - void MotionIndex::set_id(unsigned int id) - { - id_ = id; - } - unsigned int MotionIndex::id() const - { - return id_; - } - unsigned int *MotionIndex::mutable_id() - { - return &id_; - } +void MotionIndex::set_id(unsigned int id) { id_ = id; } +unsigned int MotionIndex::id() const { return id_; } +unsigned int* MotionIndex::mutable_id() { return &id_; } - bool MotionIndex::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("id")) - { - unsigned int id_int = (unsigned int)(obj["id"].GetUint()); - id_ = id_int; - } - return true; - } - bool MotionIndex::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - writer->Key("id"); - writer->Uint(id_); - writer->EndObject(); - return true; - } - bool MotionIndex::IsNullJSONData() const - { - return false; - } - - void GetMotionStateResponse::set_state(MotionState state) - { - state_ = state; - } - const MotionState GetMotionStateResponse::state() const - { - return state_; - } - MotionState *GetMotionStateResponse::mutable_state() - { - return &state_; - } +bool MotionIndex::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("id")) { + unsigned int id_int = (unsigned int)(obj["id"].GetUint()); + id_ = id_int; + } + return true; +} +bool MotionIndex::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + writer->Key("id"); + writer->Uint(id_); + writer->EndObject(); + return true; +} +bool MotionIndex::IsNullJSONData() const { return false; } - bool GetMotionStateResponse::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("state")) - { - int state_int = (int)(obj["state"].GetInt()); - switch(state_int) - { - case 0:state_ = WAIT;break; - case 1:state_ = RUNNING;break; - case 2:state_ = FINISHED;break; - default:state_ = WAIT;break; - } - } - return true; - } - bool GetMotionStateResponse::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - writer->Key("state"); - writer->Int(state_); - writer->EndObject(); - return true; - } - bool GetMotionStateResponse::IsNullJSONData() const - { - return false; - } +void GetMotionStateResponse::set_state(MotionState state) { state_ = state; } +const MotionState GetMotionStateResponse::state() const { return state_; } +MotionState* GetMotionStateResponse::mutable_state() { return &state_; } +bool GetMotionStateResponse::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("state")) { + int state_int = (int)(obj["state"].GetInt()); + switch (state_int) { + case 0: + state_ = WAIT; + break; + case 1: + state_ = RUNNING; + break; + case 2: + state_ = FINISHED; + break; + default: + state_ = WAIT; + break; + } + } + return true; +} +bool GetMotionStateResponse::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + writer->Key("state"); + writer->Int(state_); + writer->EndObject(); + return true; +} +bool GetMotionStateResponse::IsNullJSONData() const { return false; } - void JointMove::set_pose(double pose) - { - pose_ = pose; - } - const double JointMove::pose() const - { - return pose_; - } - double *JointMove::mutable_pose() - { - return &pose_; - } - void JointMove::set_velocity(double velocity) - { - velocity_ = velocity; - } - const double JointMove::velocity() const - { - return velocity_; - } - double *JointMove::mutable_velocity() - { - return &velocity_; - } - void JointMove::set_acc(double acc) - { - acc_ = acc; - } - const double JointMove::acc() const - { - return acc_; - } - double *JointMove::mutable_acc() - { - return &acc_; - } - bool JointMove::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("pose")) - { - pose_ = (double)(obj["pose"].GetDouble()); - } - if(obj.HasMember("velocity")) - { - velocity_ = (double)(obj["velocity"].GetDouble()); - } - if(obj.HasMember("acc")) - { - acc_ = (double)(obj["acc"].GetDouble()); - } - return true; - } - bool JointMove::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - writer->Key("pose"); - writer->Double(pose_); - writer->Key("velocity"); - writer->Double(velocity_); - writer->Key("acc"); - writer->Double(acc_); - writer->EndObject(); - return true; - } - bool JointMove::IsNullJSONData() const - { - return false; - } - void MovePvatRequest::set_duration(double duration) - { - duration_ = duration; - } - const double MovePvatRequest::duration() const - { - return duration_; - } - double *MovePvatRequest::mutable_duration() - { - return &duration_; - } - void MovePvatRequest::set_joints(std::vector joints) - { - joints_ = joints; - } - const std::vector MovePvatRequest::joints() const - { - return joints_; - } - std::vector *MovePvatRequest::mutable_joints() - { - return &joints_; - } - bool MovePvatRequest::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("duration")) - { - duration_ = (double)(obj["duration"].GetDouble()); - } - if(obj.HasMember("joints")) - { - std::vector j; - for(auto joint = obj["joints"].GetArray().Begin();joint != obj["joints"].GetArray().End();joint++) - { - JointMove _j; - _j.FromJSONString(joint->GetString()); - j.push_back(_j); - } - joints_ = j; - } - return true; - } - bool MovePvatRequest::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - writer->Key("duration"); - writer->Double(duration_); - writer->StartArray(); - for(auto j:joints_) - { - writer->String(j.ToJSONString().c_str()); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool MovePvatRequest::IsNullJSONData() const - { - return false; - } +void JointMove::set_pose(double pose) { pose_ = pose; } +const double JointMove::pose() const { return pose_; } +double* JointMove::mutable_pose() { return &pose_; } +void JointMove::set_velocity(double velocity) { velocity_ = velocity; } +const double JointMove::velocity() const { return velocity_; } +double* JointMove::mutable_velocity() { return &velocity_; } +void JointMove::set_acc(double acc) { acc_ = acc; } +const double JointMove::acc() const { return acc_; } +double* JointMove::mutable_acc() { return &acc_; } +bool JointMove::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("pose")) { + pose_ = (double)(obj["pose"].GetDouble()); + } + if (obj.HasMember("velocity")) { + velocity_ = (double)(obj["velocity"].GetDouble()); + } + if (obj.HasMember("acc")) { + acc_ = (double)(obj["acc"].GetDouble()); + } + return true; +} +bool JointMove::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + writer->Key("pose"); + writer->Double(pose_); + writer->Key("velocity"); + writer->Double(velocity_); + writer->Key("acc"); + writer->Double(acc_); + writer->EndObject(); + return true; +} +bool JointMove::IsNullJSONData() const { return false; } +void MovePvatRequest::set_duration(double duration) { duration_ = duration; } +const double MovePvatRequest::duration() const { return duration_; } +double* MovePvatRequest::mutable_duration() { return &duration_; } +void MovePvatRequest::set_joints(std::vector joints) { + joints_ = joints; +} +const std::vector MovePvatRequest::joints() const { return joints_; } +std::vector* MovePvatRequest::mutable_joints() { return &joints_; } +bool MovePvatRequest::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("duration")) { + duration_ = (double)(obj["duration"].GetDouble()); + } + if (obj.HasMember("joints")) { + std::vector j; + for (auto joint = obj["joints"].GetArray().Begin(); + joint != obj["joints"].GetArray().End(); joint++) { + JointMove _j; + _j.FromJSONString(joint->GetString()); + j.push_back(_j); + } + joints_ = j; + } + return true; +} +bool MovePvatRequest::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + writer->Key("duration"); + writer->Double(duration_); + writer->StartArray(); + for (auto j : joints_) { + writer->String(j.ToJSONString().c_str()); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool MovePvatRequest::IsNullJSONData() const { return false; } - // SpeedParam begin - SpeedParam::SpeedParam() - { - - } - SpeedParam::SpeedParam(const SpeedParam & other) - { - *this = other; - } - SpeedParam & SpeedParam::operator = (const SpeedParam & other) - { - acc_.reset(); - if(other.acc_) - { - acc_ = std::make_unique(*other.acc_); - } - time_.reset(); - if(other.time_) - { - time_ = std::make_unique(*other.time_); - } - constrained_.reset(); - if(other.constrained_) - { - constrained_ = std::make_unique(*other.constrained_); - } - return *this; - } - void SpeedParam::set_acc(double acc) - { - acc_ = std::make_unique(acc); - } - // double v() const; - double * SpeedParam::acc() const - { - return acc_.get(); - } - double * SpeedParam::mutable_acc() - { - if(acc_ == nullptr) - { +// SpeedParam begin +SpeedParam::SpeedParam() {} +SpeedParam::SpeedParam(const SpeedParam& other) { *this = other; } +SpeedParam& SpeedParam::operator=(const SpeedParam& other) { + acc_.reset(); + if (other.acc_) { + acc_ = std::make_unique(*other.acc_); + } + time_.reset(); + if (other.time_) { + time_ = std::make_unique(*other.time_); + } + constrained_.reset(); + if (other.constrained_) { + constrained_ = std::make_unique(*other.constrained_); + } + return *this; +} +void SpeedParam::set_acc(double acc) { acc_ = std::make_unique(acc); } +// double v() const; +double* SpeedParam::acc() const { return acc_.get(); } +double* SpeedParam::mutable_acc() { + if (acc_ == nullptr) { + acc_ = std::make_unique(); + } + return acc_.get(); +} +void SpeedParam::set_time(double time) { + time_ = std::make_unique(time); +} +double* SpeedParam::time() const { return time_.get(); } +double* SpeedParam::mutable_time() { + if (time_ == nullptr) { + time_ = std::make_unique(); + } + return time_.get(); +} +void SpeedParam::set_constrained(bool constrained) { + if (constrained_ == nullptr) { + constrained_ = std::make_unique(); + } + constrained_ = std::make_unique(constrained); +} +bool* SpeedParam::constrained() const { return constrained_.get(); } +bool* SpeedParam::mutable_constrained() { + if (constrained_ == nullptr) { + constrained_ = std::make_unique(); + } + return constrained_.get(); +} + +bool SpeedParam::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("acc")) { + if (!acc_) { acc_ = std::make_unique(); + *acc_ = obj["acc"].GetDouble(); } - return acc_.get(); - } - void SpeedParam::set_time(double time) - { - time_ = std::make_unique(time); - } - double * SpeedParam::time() const - { - return time_.get(); + } else { + acc_.reset(); } - double * SpeedParam::mutable_time() - { - if(time_ == nullptr) - { + if (obj.HasMember("time")) { + if (!time_) { time_ = std::make_unique(); + *time_ = obj["time"].GetDouble(); } - return time_.get(); - } - void SpeedParam::set_constrained(bool constrained) - { - if(constrained_ == nullptr) - { - constrained_ = std::make_unique(); - } - constrained_ = std::make_unique(constrained); - } - bool * SpeedParam::constrained() const - { - return constrained_.get(); + } else { + time_.reset(); } - bool * SpeedParam::mutable_constrained() - { - if(constrained_ == nullptr) - { + if (obj.HasMember("constrained")) { + if (!constrained_) { constrained_ = std::make_unique(); + *constrained_ = obj["constrained"].GetBool(); } - return constrained_.get(); - } - - bool SpeedParam::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("acc")) - { - if(!acc_) - { - acc_ = std::make_unique(); - *acc_ = obj["acc"].GetDouble(); - } - } - else - { - acc_.reset(); - } - if(obj.HasMember("time")) - { - if(!time_) - { - time_ = std::make_unique(); - *time_ = obj["time"].GetDouble(); - } - } - else - { - time_.reset(); - } - if(obj.HasMember("constrained")) - { - if(!constrained_) - { - constrained_ = std::make_unique(); - *constrained_ = obj["constrained"].GetBool(); - } - } - else - { - constrained_.reset(); - } - return true; + } else { + constrained_.reset(); } + return true; +} - bool SpeedParam::Serialize(rapidjson::Writer* writer) const - { - - writer->StartObject(); - if(acc_) - { - writer->String("acc"); - writer->Double(*acc_); - } - if(time_) - { - writer->String("time"); - writer->Double(*time_); - } - if(constrained_) - { - writer->String("constrained"); - writer->Bool(*constrained_); - } - writer->EndObject(); - return true; - } - bool SpeedParam::IsNullJSONData() const - { - if(acc_ || time_ || constrained_) - { - return false; - } - return true; - } - // SpeedJRequest - void SpeedJRequest::set_speed(const posture::JointPose & speed) - { - speed_ = speed; - } - const posture::JointPose & SpeedJRequest::speed() const - { - return speed_; +bool SpeedParam::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + if (acc_) { + writer->String("acc"); + writer->Double(*acc_); + } + if (time_) { + writer->String("time"); + writer->Double(*time_); + } + if (constrained_) { + writer->String("constrained"); + writer->Bool(*constrained_); + } + writer->EndObject(); + return true; +} +bool SpeedParam::IsNullJSONData() const { + if (acc_ || time_ || constrained_) { + return false; } + return true; +} +// SpeedJRequest +void SpeedJRequest::set_speed(const posture::JointPose& speed) { + speed_ = speed; +} +const posture::JointPose& SpeedJRequest::speed() const { return speed_; } - posture::JointPose * SpeedJRequest::mutable_speed() - { - return &speed_; - } - void SpeedJRequest::set_param(const SpeedParam & param) - { - param_ = param; - } - const SpeedParam & SpeedJRequest::param() const - { - return param_; - } - SpeedParam * SpeedJRequest::mutable_param() - { - return ¶m_; - } - bool SpeedJRequest::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("speed")) - { - speed_.Deserialize(obj["speed"]); - } - if(obj.HasMember("param")) - { - param_.Deserialize(obj["param"]); - } - return true; - } - bool SpeedJRequest::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - if(!speed_.IsNullJSONData()) - { - writer->String("speed"); - speed_.Serialize(writer); - } - if(!param_.IsNullJSONData()) - { - writer->String("param"); - param_.Serialize(writer); - } - writer->EndObject(); +posture::JointPose* SpeedJRequest::mutable_speed() { return &speed_; } +void SpeedJRequest::set_param(const SpeedParam& param) { param_ = param; } +const SpeedParam& SpeedJRequest::param() const { return param_; } +SpeedParam* SpeedJRequest::mutable_param() { return ¶m_; } +bool SpeedJRequest::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("speed")) { + speed_.Deserialize(obj["speed"]); + } + if (obj.HasMember("param")) { + param_.Deserialize(obj["param"]); + } + return true; +} +bool SpeedJRequest::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + if (!speed_.IsNullJSONData()) { + writer->String("speed"); + speed_.Serialize(writer); + } + if (!param_.IsNullJSONData()) { + writer->String("param"); + param_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool SpeedJRequest::IsNullJSONData() const { + if (speed_.IsNullJSONData() && param_.IsNullJSONData()) { return true; } - bool SpeedJRequest::IsNullJSONData() const - { - if(speed_.IsNullJSONData() && param_.IsNullJSONData()) - { - return true; - } - return false; - } - // SpeedJRequest end - // SpeedJRequest - void SpeedLRequest::set_speed(const posture::CartesianPose & speed) - { - speed_ = speed; - } - const posture::CartesianPose & SpeedLRequest::speed() const - { - return speed_; - } + return false; +} +// SpeedJRequest end +// SpeedJRequest +void SpeedLRequest::set_speed(const posture::CartesianPose& speed) { + speed_ = speed; +} +const posture::CartesianPose& SpeedLRequest::speed() const { return speed_; } - posture::CartesianPose * SpeedLRequest::mutable_speed() - { - return &speed_; - } - void SpeedLRequest::set_param(const SpeedParam & param) - { - param_ = param; - } - const SpeedParam & SpeedLRequest::param() const - { - return param_; - } - SpeedParam * SpeedLRequest::mutable_param() - { - return ¶m_; - } - void SpeedLRequest::set_frame(const posture::CartesianFrame & frame) - { - frame_ = frame; - } - const posture::CartesianFrame & SpeedLRequest::frame() const - { - return frame_; - } - posture::CartesianFrame * SpeedLRequest::mutable_frame() - { - return &frame_; - } - bool SpeedLRequest::Deserialize(const rapidjson::Value& obj) - { - if(obj.HasMember("speed")) - { - speed_.Deserialize(obj["speed"]); - } - if(obj.HasMember("param")) - { - param_.Deserialize(obj["param"]); - } - if(obj.HasMember("frame")) - { - frame_.Deserialize(obj["frame"]); - } - return true; - } - bool SpeedLRequest::Serialize(rapidjson::Writer* writer) const - { - writer->StartObject(); - if(!speed_.IsNullJSONData()) - { - writer->String("speed"); - speed_.Serialize(writer); - } - if(!param_.IsNullJSONData()) - { - writer->String("param"); - param_.Serialize(writer); - } - if(!frame_.IsNullJSONData()) - { - writer->String("frame"); - frame_.Serialize(writer); - } - writer->EndObject(); +posture::CartesianPose* SpeedLRequest::mutable_speed() { return &speed_; } +void SpeedLRequest::set_param(const SpeedParam& param) { param_ = param; } +const SpeedParam& SpeedLRequest::param() const { return param_; } +SpeedParam* SpeedLRequest::mutable_param() { return ¶m_; } +void SpeedLRequest::set_frame(const posture::CartesianFrame& frame) { + frame_ = frame; +} +const posture::CartesianFrame& SpeedLRequest::frame() const { return frame_; } +posture::CartesianFrame* SpeedLRequest::mutable_frame() { return &frame_; } +bool SpeedLRequest::Deserialize(const rapidjson::Value& obj) { + if (obj.HasMember("speed")) { + speed_.Deserialize(obj["speed"]); + } + if (obj.HasMember("param")) { + param_.Deserialize(obj["param"]); + } + if (obj.HasMember("frame")) { + frame_.Deserialize(obj["frame"]); + } + return true; +} +bool SpeedLRequest::Serialize( + rapidjson::Writer* writer) const { + writer->StartObject(); + if (!speed_.IsNullJSONData()) { + writer->String("speed"); + speed_.Serialize(writer); + } + if (!param_.IsNullJSONData()) { + writer->String("param"); + param_.Serialize(writer); + } + if (!frame_.IsNullJSONData()) { + writer->String("frame"); + frame_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool SpeedLRequest::IsNullJSONData() const { + if (speed_.IsNullJSONData() && param_.IsNullJSONData()) { return true; } - bool SpeedLRequest::IsNullJSONData() const - { - if(speed_.IsNullJSONData() && param_.IsNullJSONData()) - { - return true; - } - return false; - } - // SpeedJRequest end - } -} \ No newline at end of file + return false; +} +// SpeedJRequest end +} // namespace motion +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/motion.hh b/sdk/src/protos/motion.hh index 945b33e..afa1534 100644 --- a/sdk/src/protos/motion.hh +++ b/sdk/src/protos/motion.hh @@ -7,236 +7,247 @@ #include #include -namespace lebai -{ - namespace motion - { - class MoveParam : public JSONBase - { - public: - MoveParam(); - MoveParam(const MoveParam & other); - MoveParam & operator = (const MoveParam & other); - void set_velocity(double); - double * velocity() const; - double * mutable_velocity(); - void set_acc(double); - double * acc() const; - double * mutable_acc(); - void set_time(double); - double * t() const; - double * mutable_time(); - void set_radius(double); - double * radius() const; - double * mutable_radius(); - protected: - std::unique_ptr velocity_ = nullptr; - std::unique_ptr acc_ = nullptr; - std::unique_ptr time_ = nullptr; - std::unique_ptr radius_ = nullptr; - - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class MoveRequest : public JSONBase - { - public: - // MoveRequest(const MoveRequest & other); - void set_param(const MoveParam & param); - const MoveParam & param() const; - MoveParam * mutable_param(); - void set_pose(const posture::Pose & pose); - const posture::Pose & pose() const; - posture::Pose * mutable_pose(); - protected: - MoveParam param_; - posture::Pose pose_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class MovecRequest : public JSONBase - { - public: - // pose_via_ - void set_pose_via(const posture::Pose & pose); - const posture::Pose & pose_via() const; - posture::Pose * mutable_pose_via(); - // pose_ - void set_pose(const posture::Pose & pose); - const posture::Pose & pose() const; - posture::Pose * mutable_pose(); - // param_ - void set_param(const MoveParam & param); - const MoveParam & param() const; - MoveParam * mutable_param(); - // rad_ - void set_rad(double rad); - double rad() const; - double * mutable_rad(); - - protected: - posture::Pose pose_via_; - posture::Pose pose_; - double rad_; - MoveParam param_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class MotionIndex : public JSONBase - { - public: - void set_id(unsigned int id); - unsigned int id() const; - unsigned int * mutable_id(); - protected: - unsigned int id_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - enum MotionState - { - WAIT = 0, - RUNNING = 1, - FINISHED = 2, - }; - - class GetMotionStateResponse : public JSONBase - { - public: - void set_state(MotionState state); - const MotionState state() const; - MotionState * mutable_state(); - protected: - MotionState state_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class JointMove : public JSONBase - { - public: - void set_pose(double pose); - const double pose() const; - double * mutable_pose(); - void set_velocity(double velocity); - const double velocity() const; - double * mutable_velocity(); - void set_acc(double acc); - const double acc() const; - double * mutable_acc(); - protected: - double pose_; - double velocity_; - double acc_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class MovePvatRequest : public JSONBase - { - public: - void set_duration(double duration); - const double duration() const; - double * mutable_duration(); - void set_joints(std::vector joints); - const std::vector joints() const; - std::vector * mutable_joints(); - protected: - double duration_; - std::vector joints_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class SpeedParam : public JSONBase - { - public: - SpeedParam(); - SpeedParam(const SpeedParam & other); - SpeedParam & operator = (const SpeedParam & other); - void set_acc(double duration); - double * acc() const; - double * mutable_acc(); - void set_time(double time); - double * time() const; - double * mutable_time(); - void set_constrained(bool constrained); - bool * constrained() const; - bool * mutable_constrained(); - - protected: - std::unique_ptr acc_ = nullptr; - std::unique_ptr time_ = nullptr; - std::unique_ptr constrained_ = nullptr; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class SpeedJRequest : public JSONBase - { - public: - void set_speed(const posture::JointPose & speed); - const posture::JointPose & speed() const; - posture::JointPose * mutable_speed(); - void set_param(const SpeedParam & param); - const SpeedParam & param() const; - SpeedParam * mutable_param(); - protected: - posture::JointPose speed_; - SpeedParam param_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - - class SpeedLRequest : public JSONBase - { - public: - void set_speed(const posture::CartesianPose & speed); - const posture::CartesianPose & speed() const; - posture::CartesianPose * mutable_speed(); - void set_param(const SpeedParam & param); - const SpeedParam & param() const; - SpeedParam * mutable_param(); - void set_frame(const posture::CartesianFrame & param); - const posture::CartesianFrame & frame() const; - posture::CartesianFrame * mutable_frame(); - - protected: - posture::CartesianPose speed_; - SpeedParam param_; - posture::CartesianFrame frame_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +namespace lebai { +namespace motion { +class MoveParam : public JSONBase { + public: + MoveParam(); + MoveParam(const MoveParam& other); + MoveParam& operator=(const MoveParam& other); + void set_velocity(double); + double* velocity() const; + double* mutable_velocity(); + void set_acc(double); + double* acc() const; + double* mutable_acc(); + void set_time(double); + double* t() const; + double* mutable_time(); + void set_radius(double); + double* radius() const; + double* mutable_radius(); + + protected: + std::unique_ptr velocity_ = nullptr; + std::unique_ptr acc_ = nullptr; + std::unique_ptr time_ = nullptr; + std::unique_ptr radius_ = nullptr; + + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class MoveRequest : public JSONBase { + public: + // MoveRequest(const MoveRequest & other); + void set_param(const MoveParam& param); + const MoveParam& param() const; + MoveParam* mutable_param(); + void set_pose(const posture::Pose& pose); + const posture::Pose& pose() const; + posture::Pose* mutable_pose(); + + protected: + MoveParam param_; + posture::Pose pose_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class MovecRequest : public JSONBase { + public: + // pose_via_ + void set_pose_via(const posture::Pose& pose); + const posture::Pose& pose_via() const; + posture::Pose* mutable_pose_via(); + // pose_ + void set_pose(const posture::Pose& pose); + const posture::Pose& pose() const; + posture::Pose* mutable_pose(); + // param_ + void set_param(const MoveParam& param); + const MoveParam& param() const; + MoveParam* mutable_param(); + // rad_ + void set_rad(double rad); + double rad() const; + double* mutable_rad(); + + protected: + posture::Pose pose_via_; + posture::Pose pose_; + double rad_; + MoveParam param_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class MotionIndex : public JSONBase { + public: + void set_id(unsigned int id); + unsigned int id() const; + unsigned int* mutable_id(); + + protected: + unsigned int id_; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +enum MotionState { + WAIT = 0, + RUNNING = 1, + FINISHED = 2, +}; + +class GetMotionStateResponse : public JSONBase { + public: + void set_state(MotionState state); + const MotionState state() const; + MotionState* mutable_state(); + + protected: + MotionState state_; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class JointMove : public JSONBase { + public: + void set_pose(double pose); + const double pose() const; + double* mutable_pose(); + void set_velocity(double velocity); + const double velocity() const; + double* mutable_velocity(); + void set_acc(double acc); + const double acc() const; + double* mutable_acc(); + + protected: + double pose_; + double velocity_; + double acc_; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class MovePvatRequest : public JSONBase { + public: + void set_duration(double duration); + const double duration() const; + double* mutable_duration(); + void set_joints(std::vector joints); + const std::vector joints() const; + std::vector* mutable_joints(); + + protected: + double duration_; + std::vector joints_; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class SpeedParam : public JSONBase { + public: + SpeedParam(); + SpeedParam(const SpeedParam& other); + SpeedParam& operator=(const SpeedParam& other); + void set_acc(double duration); + double* acc() const; + double* mutable_acc(); + void set_time(double time); + double* time() const; + double* mutable_time(); + void set_constrained(bool constrained); + bool* constrained() const; + bool* mutable_constrained(); + + protected: + std::unique_ptr acc_ = nullptr; + std::unique_ptr time_ = nullptr; + std::unique_ptr constrained_ = nullptr; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class SpeedJRequest : public JSONBase { + public: + void set_speed(const posture::JointPose& speed); + const posture::JointPose& speed() const; + posture::JointPose* mutable_speed(); + void set_param(const SpeedParam& param); + const SpeedParam& param() const; + SpeedParam* mutable_param(); + + protected: + posture::JointPose speed_; + SpeedParam param_; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +class SpeedLRequest : public JSONBase { + public: + void set_speed(const posture::CartesianPose& speed); + const posture::CartesianPose& speed() const; + posture::CartesianPose* mutable_speed(); + void set_param(const SpeedParam& param); + const SpeedParam& param() const; + SpeedParam* mutable_param(); + void set_frame(const posture::CartesianFrame& param); + const posture::CartesianFrame& frame() const; + posture::CartesianFrame* mutable_frame(); + + protected: + posture::CartesianPose speed_; + SpeedParam param_; + posture::CartesianFrame frame_; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace motion +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/posture.cc b/sdk/src/protos/posture.cc index a4ba49b..0cc9bac 100755 --- a/sdk/src/protos/posture.cc +++ b/sdk/src/protos/posture.cc @@ -1,980 +1,805 @@ -#include "posture.hh" - #include -#include - -namespace lebai -{ - namespace posture - { - void JointPose::set_joint(const std::vector &joint) { joint_ = joint; } - std::vector JointPose::joint() const { return joint_; } - std::vector *JointPose::mutable_joint() { return &joint_; } - bool JointPose::Deserialize(const rapidjson::Value &obj) - { - joint_.clear(); - for (auto iter = obj["joint"].GetArray().Begin(); - iter != obj["joint"].GetArray().End(); iter++) - { - joint_.push_back(iter->GetDouble()); - } - return true; - } - - bool JointPose::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("joint"); - writer->StartArray(); - for (auto it = joint_.begin(); it != joint_.end(); ++it) - { - writer->Double(*it); - } - writer->EndArray(); - writer->EndObject(); - return true; - } - bool JointPose::IsNullJSONData() const { return joint_.empty(); } - - void Position::set_x(double x) { x_ = x; } - double Position::x() const { return x_; } - double *Position::mutable_x() { return &x_; } - void Position::set_y(double y) { y_ = y; } - double Position::y() const { return y_; } - double *Position::mutable_y() { return &y_; } - void Position::set_z(double z) { z_ = z; } - double Position::z() const { return z_; } - double *Position::mutable_z() { return &z_; } - bool Position::Deserialize(const rapidjson::Value &obj) - { - x_ = obj["x"].GetDouble(); - y_ = obj["y"].GetDouble(); - z_ = obj["z"].GetDouble(); - return true; - } - bool Position::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("x"); - writer->Double(x_); - writer->String("y"); - writer->Double(y_); - writer->String("z"); - writer->Double(z_); - writer->EndObject(); - return true; - } - bool Position::IsNullJSONData() const - { - return std::abs(x_) < 1e-6 && std::abs(y_) < 1e-6 && std::abs(z_) < 1e-6; - } - - void Quaternion::set_w(double w) { w_ = w; } - double Quaternion::w() const { return w_; } - double *Quaternion::mutable_w() { return &w_; } - void Quaternion::set_i(double i) { i_ = i; } - double Quaternion::i() const { return i_; } - double *Quaternion::mutable_i() { return &i_; } - void Quaternion::set_j(double j) { j_ = j; } - double Quaternion::j() const { return j_; } - double *Quaternion::mutable_j() { return &j_; } - void Quaternion::set_k(double k) { k_ = k; } - double Quaternion::k() const { return k_; } - double *Quaternion::mutable_k() { return &k_; } - bool Quaternion::Deserialize(const rapidjson::Value &obj) - { - w_ = obj["w"].GetDouble(); - i_ = obj["i"].GetDouble(); - j_ = obj["j"].GetDouble(); - k_ = obj["k"].GetDouble(); - return true; - } - bool Quaternion::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("w"); - writer->Double(w_); - writer->String("i"); - writer->Double(i_); - writer->String("j"); - writer->Double(j_); - writer->String("k"); - writer->Double(k_); - writer->EndObject(); - return true; - } - bool Quaternion::IsNullJSONData() const - { - return std::abs(w_ - 1.0) < 1e-6 && std::abs(i_) < 1e-6 && - std::abs(j_) < 1e-6 && std::abs(k_) < 1e-6; - } - - void RotationMatrix::set_data(const std::array &data) - { - data_ = data; - } - const std::array &RotationMatrix::data() const { return data_; } - std::array *RotationMatrix::mutable_data() { return &data_; } - bool RotationMatrix::Deserialize(const rapidjson::Value &obj) - { - data_[0] = obj["m11"].GetDouble(); - data_[1] = obj["m12"].GetDouble(); - data_[2] = obj["m13"].GetDouble(); - data_[3] = obj["m21"].GetDouble(); - data_[4] = obj["m22"].GetDouble(); - data_[5] = obj["m23"].GetDouble(); - data_[6] = obj["m31"].GetDouble(); - data_[7] = obj["m32"].GetDouble(); - data_[8] = obj["m33"].GetDouble(); - return true; - } - bool RotationMatrix::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("m11"); - writer->Double(data_[0]); - writer->String("m12"); - writer->Double(data_[1]); - writer->String("m13"); - writer->Double(data_[2]); - writer->String("m21"); - writer->Double(data_[3]); - writer->String("m22"); - writer->Double(data_[4]); - writer->String("m23"); - writer->Double(data_[5]); - writer->String("m31"); - writer->Double(data_[6]); - writer->String("m32"); - writer->Double(data_[7]); - writer->String("m33"); - writer->Double(data_[8]); - writer->EndObject(); - return true; - } - bool RotationMatrix::IsNullJSONData() const - { - return std::abs(data_[0] - 1) < 1e-6 && std::abs(data_[1]) < 1e-6 && - std::abs(data_[2]) < 1e-6 && std::abs(data_[3]) < 1e-6 && - std::abs(data_[4] - 1) < 1e-6 && std::abs(data_[5]) < 1e-6 && - std::abs(data_[6]) < 1e-6 && std::abs(data_[7]) < 1e-6 && - std::abs(data_[8] - 1) < 1e-6; - } - Rotation::Rotation() {} - Rotation::Rotation(const Rotation &other) - { - if (other.matrix_) - { - matrix_ = std::make_unique(); - *matrix_ = *other.matrix_; - } - else - { - matrix_.reset(); - } - if (other.quaternion_) - { - quaternion_ = std::make_unique(); - *quaternion_ = *other.quaternion_; - } - else - { - quaternion_.reset(); - } - if (other.euler_zyx_) - { - euler_zyx_ = std::make_unique(); - *euler_zyx_ = *other.euler_zyx_; - } - else - { - euler_zyx_.reset(); - } - } - Rotation &Rotation::operator=(const Rotation &other) - { - if (other.matrix_) - { - matrix_ = std::make_unique(); - *matrix_ = *other.matrix_; - } - else - { - matrix_.reset(); - } - if (other.quaternion_) - { - quaternion_ = std::make_unique(); - *quaternion_ = *other.quaternion_; - } - else - { - quaternion_.reset(); - } - if (other.euler_zyx_) - { - euler_zyx_ = std::make_unique(); - *euler_zyx_ = *other.euler_zyx_; - } - else - { - euler_zyx_.reset(); - } - return *this; - } - void Rotation::set_rotation_matrix(const RotationMatrix &matrix) - { - if (!matrix_) - { - matrix_ = std::make_unique(); - } - *matrix_ = matrix; - } - const RotationMatrix *Rotation::rotation_matrix() const - { - return matrix_.get(); - } - RotationMatrix *Rotation::mutable_rotation_matrix() - { - if (!matrix_) - { - euler_zyx_.reset(); - quaternion_.reset(); - matrix_ = std::make_unique(); - } - return matrix_.get(); - } - - void Rotation::set_quaternion(const Quaternion &quaternion) - { - if (!quaternion_) - { - quaternion_ = std::make_unique(); - } - *quaternion_ = quaternion; - } - const Quaternion *Rotation::quaternion() const { return quaternion_.get(); } - Quaternion *Rotation::mutable_quaternion() - { - if (!quaternion_) - { - quaternion_ = std::make_unique(); - } - return quaternion_.get(); - } - void Rotation::set_euler_zyx(const Position &euler_zyx) - { - if (!euler_zyx_) - { - euler_zyx_ = std::make_unique(); - } - *euler_zyx_ = euler_zyx; - } - const Position *Rotation::euler_zyx() const { return euler_zyx_.get(); } - Position *Rotation::mutable_euler_zyx() - { - if (!euler_zyx_) - { - euler_zyx_ = std::make_unique(); - } - return euler_zyx_.get(); - } - bool Rotation::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("matrix")) - { - matrix_ = std::make_unique(); - matrix_->Deserialize(obj["matrix"]); - } - else - { - matrix_.reset(); - } - if (obj.HasMember("quaternion")) - { - quaternion_ = std::make_unique(); - quaternion_->Deserialize(obj["quaternion"]); - } - else - { - quaternion_.reset(); - } - if (obj.HasMember("euler_zyx")) - { - euler_zyx_ = std::make_unique(); - euler_zyx_->Deserialize(obj["euler_zyx"]); - } - else - { - euler_zyx_.reset(); - } - return true; - } - bool Rotation::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - if (matrix_ != nullptr) - { - writer->String("matrix"); - matrix_->Serialize(writer); - } - if (quaternion_ != nullptr) - { - writer->String("quaternion"); - quaternion_->Serialize(writer); - } - if (euler_zyx_ != nullptr) - { - writer->String("euler_zyx"); - euler_zyx_->Serialize(writer); - } - writer->EndObject(); - return true; - } - bool Rotation::IsNullJSONData() const - { - if (matrix_ && !matrix_->IsNullJSONData()) - { - return false; - } - if (quaternion_ && !quaternion_->IsNullJSONData()) - { - return false; - } - if (euler_zyx_ && !euler_zyx_->IsNullJSONData()) - { - return false; - } - return true; - } - - void JointFrame::set_kind(Kind kind) { kind_ = kind; } - JointFrame::Kind JointFrame::kind() const { return kind_; } - JointFrame::Kind *JointFrame::mutable_kind() { return &kind_; } - void JointFrame::set_joints(const JointPose &joints) { joints_ = joints; } - const JointPose &JointFrame::joints() const { return joints_; } - JointPose *JointFrame::mutable_joints() { return &joints_; } - - bool JointFrame::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("kind")) - { - kind_ = static_cast(obj["kind"].GetInt()); - } - if (obj.HasMember("joints")) - { - joints_.Deserialize(obj["joints"]); - } - return true; - } - - bool JointFrame::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - if (kind_ != Kind::BASE) - { - writer->String("kind"); - writer->Int(static_cast(kind_)); - } - if (joints_.joint().size() > 0) - { - writer->String("joints"); - joints_.Serialize(writer); - } - writer->EndObject(); - return true; - } - bool JointFrame::IsNullJSONData() const - { - return joints_.IsNullJSONData() && kind_ == Kind::BASE; - } - - void CartesianFrame::set_position_kind(Kind position_kind) - { - position_kind_ = position_kind; - } - CartesianFrame::Kind CartesianFrame::position_kind() const - { - return position_kind_; - } - CartesianFrame::Kind *CartesianFrame::mutable_position_kind() - { - return &position_kind_; - } - void CartesianFrame::set_position(const Position &position) - { - position_ = position; - } - const Position &CartesianFrame::position() const { return position_; } - Position *CartesianFrame::mutable_position() { return &position_; } - void CartesianFrame::set_rotation_kind(Kind rotation_kind) - { - rotation_kind_ = rotation_kind; - } - CartesianFrame::Kind CartesianFrame::rotation_kind() const - { - return rotation_kind_; - } - CartesianFrame::Kind *CartesianFrame::mutable_rotation_kind() - { - return &rotation_kind_; - } - void CartesianFrame::set_rotation(const Rotation &rotation) - { - rotation_ = rotation; - } - const Rotation &CartesianFrame::rotation() const { return rotation_; } - Rotation *CartesianFrame::mutable_rotation() { return &rotation_; } - bool CartesianFrame::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("position_kind")) - { - position_kind_ = static_cast(obj["position_kind"].GetInt()); - } - if (obj.HasMember("position")) - { - position_.Deserialize(obj["position"]); - } - if (obj.HasMember("rotation_kind")) - { - rotation_kind_ = static_cast(obj["rotation_kind"].GetInt()); - } - if (obj.HasMember("rotation")) - { - rotation_.Deserialize(obj["rotation"]); - } - return true; - } - bool CartesianFrame::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - if (position_kind_ != Kind::BASE) - { - writer->String("position_kind"); - writer->Int(static_cast(position_kind_)); - } - if (!position_.IsNullJSONData()) - { - writer->String("position"); - position_.Serialize(writer); - } - if (rotation_kind_ != Kind::BASE) - { - writer->String("rotation_kind"); - writer->Int(static_cast(rotation_kind_)); - } - if (!rotation_.IsNullJSONData()) - { - writer->String("rotation"); - rotation_.Serialize(writer); - } - writer->EndObject(); - return true; - } - bool CartesianFrame::IsNullJSONData() const - { - return position_.IsNullJSONData() && rotation_.IsNullJSONData() && - position_kind_ == Kind::BASE && rotation_kind_ == Kind::BASE; - } - - void CartesianPose::set_position(const Position &position) - { - position_ = position; - } - const Position &CartesianPose::position() const { return position_; } - Position *CartesianPose::mutable_position() { return &position_; } - void CartesianPose::set_rotation(const Rotation &rotation) - { - rotation_ = rotation; - } - const Rotation &CartesianPose::rotation() const { return rotation_; } - Rotation *CartesianPose::mutable_rotation() { return &rotation_; } - bool CartesianPose::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("position")) - { - position_.Deserialize(obj["position"]); - } - if (obj.HasMember("rotation")) - { - rotation_.Deserialize(obj["rotation"]); - } - return true; - } - bool CartesianPose::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - if (!position_.IsNullJSONData()) - { - writer->String("position"); - position_.Serialize(writer); - } - if (!rotation_.IsNullJSONData()) - { - writer->String("rotation"); - rotation_.Serialize(writer); - } - writer->EndObject(); - return true; - } - bool CartesianPose::IsNullJSONData() const - { - return position_.IsNullJSONData() && rotation_.IsNullJSONData(); - } +#include "posture.hh" - // // JointTargetPose begin - // void JointTargetPose::set_base(const JointFrame &base) { base_ = base; } - // const JointFrame &JointTargetPose::base() const { return base_; } - // JointFrame *JointTargetPose::mutable_base() { return &base_; } - // void JointTargetPose::set_delta(const JointPose &joints) { delta_ = joints; } - // const JointPose &JointTargetPose::delta() const { return delta_; } - // JointPose *JointTargetPose::mutable_delta() { return &delta_; } - // bool JointTargetPose::Deserialize(const rapidjson::Value &obj) - // { - // if (obj.HasMember("base")) - // { - // base_.Deserialize(obj["base"]); - // } - // if (obj.HasMember("delta")) - // { - // delta_.Deserialize(obj["delta"]); - // } - // return true; - // } - // bool JointTargetPose::Serialize( - // rapidjson::Writer *writer) const - // { - // writer->StartObject(); - // if (!base_.IsNullJSONData()) - // { - // writer->String("base"); - // base_.Serialize(writer); - // } - // if (!delta_.IsNullJSONData()) - // { - // writer->String("delta"); - // delta_.Serialize(writer); - // } - // writer->EndObject(); - // return true; - // } - // bool JointTargetPose::IsNullJSONData() const - // { - // return base_.IsNullJSONData() && delta_.IsNullJSONData(); - // } - // // JointTargetPose end - - // // CartesianTargetPose begin - // void CartesianTargetPose::set_base(const CartesianFrame &base) { base_ = base; } - // const CartesianFrame &CartesianTargetPose::base() const { return base_; } - // CartesianFrame *CartesianTargetPose::mutable_base() { return &base_; } - // void CartesianTargetPose::set_delta(const CartesianPose &delta) - // { - // delta_ = delta; - // } - // const CartesianPose &CartesianTargetPose::delta() const { return delta_; } - // CartesianPose *CartesianTargetPose::mutable_delta() { return &delta_; } - // bool CartesianTargetPose::Deserialize(const rapidjson::Value &obj) - // { - // if (obj.HasMember("base")) - // { - // base_.Deserialize(obj["base"]); - // } - // if (obj.HasMember("delta")) - // { - // delta_.Deserialize(obj["delta"]); - // } - // return true; - // } - // bool CartesianTargetPose::Serialize( - // rapidjson::Writer *writer) const - // { - // writer->StartObject(); - // if (!base_.IsNullJSONData()) - // { - // writer->String("base"); - // base_.Serialize(writer); - // } - // if (!delta_.IsNullJSONData()) - // { - // writer->String("delta"); - // delta_.Serialize(writer); - // } - // writer->EndObject(); - // return true; - // } - // bool CartesianTargetPose::IsNullJSONData() const - // { - // return base_.IsNullJSONData() && delta_.IsNullJSONData(); - // } - // // CartesianTargetPose end - - // Pose begin - Pose &Pose::operator=(const Pose &other) - { - kind_ = other.kind_; - joint_.reset(); - cart_.reset(); - cart_frame_index_.reset(); - cart_frame_.reset(); - if (kind_ == JOINT) - { - joint_ = std::make_unique(); - *joint_ = *other.joint_; - } - else - { - cart_ = std::make_unique(); - *cart_ = *other.cart_; - cart_frame_index_ = std::make_unique(); - *cart_frame_index_ = *other.cart_frame_index_; - cart_frame_ = std::make_unique(); - *cart_frame_ = *other.cart_frame_; - } - return *this; - } - void Pose::set_kind(Kind kind) - { - kind_ = kind; - joint_.reset(); - cart_.reset(); - cart_frame_index_.reset(); - cart_frame_.reset(); - if (kind_ == JOINT) - { +namespace lebai { +namespace posture { +void JointPose::set_joint(const std::vector &joint) { joint_ = joint; } +std::vector JointPose::joint() const { return joint_; } +std::vector *JointPose::mutable_joint() { return &joint_; } +bool JointPose::Deserialize(const rapidjson::Value &obj) { + joint_.clear(); + for (auto iter = obj["joint"].GetArray().Begin(); + iter != obj["joint"].GetArray().End(); iter++) { + joint_.push_back(iter->GetDouble()); + } + return true; +} + +bool JointPose::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("joint"); + writer->StartArray(); + for (auto it = joint_.begin(); it != joint_.end(); ++it) { + writer->Double(*it); + } + writer->EndArray(); + writer->EndObject(); + return true; +} +bool JointPose::IsNullJSONData() const { return joint_.empty(); } + +void Position::set_x(double x) { x_ = x; } +double Position::x() const { return x_; } +double *Position::mutable_x() { return &x_; } +void Position::set_y(double y) { y_ = y; } +double Position::y() const { return y_; } +double *Position::mutable_y() { return &y_; } +void Position::set_z(double z) { z_ = z; } +double Position::z() const { return z_; } +double *Position::mutable_z() { return &z_; } +bool Position::Deserialize(const rapidjson::Value &obj) { + x_ = obj["x"].GetDouble(); + y_ = obj["y"].GetDouble(); + z_ = obj["z"].GetDouble(); + return true; +} +bool Position::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("x"); + writer->Double(x_); + writer->String("y"); + writer->Double(y_); + writer->String("z"); + writer->Double(z_); + writer->EndObject(); + return true; +} +bool Position::IsNullJSONData() const { + return std::abs(x_) < 1e-6 && std::abs(y_) < 1e-6 && std::abs(z_) < 1e-6; +} + +void Quaternion::set_w(double w) { w_ = w; } +double Quaternion::w() const { return w_; } +double *Quaternion::mutable_w() { return &w_; } +void Quaternion::set_i(double i) { i_ = i; } +double Quaternion::i() const { return i_; } +double *Quaternion::mutable_i() { return &i_; } +void Quaternion::set_j(double j) { j_ = j; } +double Quaternion::j() const { return j_; } +double *Quaternion::mutable_j() { return &j_; } +void Quaternion::set_k(double k) { k_ = k; } +double Quaternion::k() const { return k_; } +double *Quaternion::mutable_k() { return &k_; } +bool Quaternion::Deserialize(const rapidjson::Value &obj) { + w_ = obj["w"].GetDouble(); + i_ = obj["i"].GetDouble(); + j_ = obj["j"].GetDouble(); + k_ = obj["k"].GetDouble(); + return true; +} +bool Quaternion::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("w"); + writer->Double(w_); + writer->String("i"); + writer->Double(i_); + writer->String("j"); + writer->Double(j_); + writer->String("k"); + writer->Double(k_); + writer->EndObject(); + return true; +} +bool Quaternion::IsNullJSONData() const { + return std::abs(w_ - 1.0) < 1e-6 && std::abs(i_) < 1e-6 && + std::abs(j_) < 1e-6 && std::abs(k_) < 1e-6; +} + +void RotationMatrix::set_data(const std::array &data) { + data_ = data; +} +const std::array &RotationMatrix::data() const { return data_; } +std::array *RotationMatrix::mutable_data() { return &data_; } +bool RotationMatrix::Deserialize(const rapidjson::Value &obj) { + data_[0] = obj["m11"].GetDouble(); + data_[1] = obj["m12"].GetDouble(); + data_[2] = obj["m13"].GetDouble(); + data_[3] = obj["m21"].GetDouble(); + data_[4] = obj["m22"].GetDouble(); + data_[5] = obj["m23"].GetDouble(); + data_[6] = obj["m31"].GetDouble(); + data_[7] = obj["m32"].GetDouble(); + data_[8] = obj["m33"].GetDouble(); + return true; +} +bool RotationMatrix::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("m11"); + writer->Double(data_[0]); + writer->String("m12"); + writer->Double(data_[1]); + writer->String("m13"); + writer->Double(data_[2]); + writer->String("m21"); + writer->Double(data_[3]); + writer->String("m22"); + writer->Double(data_[4]); + writer->String("m23"); + writer->Double(data_[5]); + writer->String("m31"); + writer->Double(data_[6]); + writer->String("m32"); + writer->Double(data_[7]); + writer->String("m33"); + writer->Double(data_[8]); + writer->EndObject(); + return true; +} +bool RotationMatrix::IsNullJSONData() const { + return std::abs(data_[0] - 1) < 1e-6 && std::abs(data_[1]) < 1e-6 && + std::abs(data_[2]) < 1e-6 && std::abs(data_[3]) < 1e-6 && + std::abs(data_[4] - 1) < 1e-6 && std::abs(data_[5]) < 1e-6 && + std::abs(data_[6]) < 1e-6 && std::abs(data_[7]) < 1e-6 && + std::abs(data_[8] - 1) < 1e-6; +} +Rotation::Rotation() {} +Rotation::Rotation(const Rotation &other) { + if (other.matrix_) { + matrix_ = std::make_unique(); + *matrix_ = *other.matrix_; + } else { + matrix_.reset(); + } + if (other.quaternion_) { + quaternion_ = std::make_unique(); + *quaternion_ = *other.quaternion_; + } else { + quaternion_.reset(); + } + if (other.euler_zyx_) { + euler_zyx_ = std::make_unique(); + *euler_zyx_ = *other.euler_zyx_; + } else { + euler_zyx_.reset(); + } +} +Rotation &Rotation::operator=(const Rotation &other) { + if (other.matrix_) { + matrix_ = std::make_unique(); + *matrix_ = *other.matrix_; + } else { + matrix_.reset(); + } + if (other.quaternion_) { + quaternion_ = std::make_unique(); + *quaternion_ = *other.quaternion_; + } else { + quaternion_.reset(); + } + if (other.euler_zyx_) { + euler_zyx_ = std::make_unique(); + *euler_zyx_ = *other.euler_zyx_; + } else { + euler_zyx_.reset(); + } + return *this; +} +void Rotation::set_rotation_matrix(const RotationMatrix &matrix) { + if (!matrix_) { + matrix_ = std::make_unique(); + } + *matrix_ = matrix; +} +const RotationMatrix *Rotation::rotation_matrix() const { + return matrix_.get(); +} +RotationMatrix *Rotation::mutable_rotation_matrix() { + if (!matrix_) { + euler_zyx_.reset(); + quaternion_.reset(); + matrix_ = std::make_unique(); + } + return matrix_.get(); +} + +void Rotation::set_quaternion(const Quaternion &quaternion) { + if (!quaternion_) { + quaternion_ = std::make_unique(); + } + *quaternion_ = quaternion; +} +const Quaternion *Rotation::quaternion() const { return quaternion_.get(); } +Quaternion *Rotation::mutable_quaternion() { + if (!quaternion_) { + quaternion_ = std::make_unique(); + } + return quaternion_.get(); +} +void Rotation::set_euler_zyx(const Position &euler_zyx) { + if (!euler_zyx_) { + euler_zyx_ = std::make_unique(); + } + *euler_zyx_ = euler_zyx; +} +const Position *Rotation::euler_zyx() const { return euler_zyx_.get(); } +Position *Rotation::mutable_euler_zyx() { + if (!euler_zyx_) { + euler_zyx_ = std::make_unique(); + } + return euler_zyx_.get(); +} +bool Rotation::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("matrix")) { + matrix_ = std::make_unique(); + matrix_->Deserialize(obj["matrix"]); + } else { + matrix_.reset(); + } + if (obj.HasMember("quaternion")) { + quaternion_ = std::make_unique(); + quaternion_->Deserialize(obj["quaternion"]); + } else { + quaternion_.reset(); + } + if (obj.HasMember("euler_zyx")) { + euler_zyx_ = std::make_unique(); + euler_zyx_->Deserialize(obj["euler_zyx"]); + } else { + euler_zyx_.reset(); + } + return true; +} +bool Rotation::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + if (matrix_ != nullptr) { + writer->String("matrix"); + matrix_->Serialize(writer); + } + if (quaternion_ != nullptr) { + writer->String("quaternion"); + quaternion_->Serialize(writer); + } + if (euler_zyx_ != nullptr) { + writer->String("euler_zyx"); + euler_zyx_->Serialize(writer); + } + writer->EndObject(); + return true; +} +bool Rotation::IsNullJSONData() const { + if (matrix_ && !matrix_->IsNullJSONData()) { + return false; + } + if (quaternion_ && !quaternion_->IsNullJSONData()) { + return false; + } + if (euler_zyx_ && !euler_zyx_->IsNullJSONData()) { + return false; + } + return true; +} + +void JointFrame::set_kind(Kind kind) { kind_ = kind; } +JointFrame::Kind JointFrame::kind() const { return kind_; } +JointFrame::Kind *JointFrame::mutable_kind() { return &kind_; } +void JointFrame::set_joints(const JointPose &joints) { joints_ = joints; } +const JointPose &JointFrame::joints() const { return joints_; } +JointPose *JointFrame::mutable_joints() { return &joints_; } + +bool JointFrame::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("kind")) { + kind_ = static_cast(obj["kind"].GetInt()); + } + if (obj.HasMember("joints")) { + joints_.Deserialize(obj["joints"]); + } + return true; +} + +bool JointFrame::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + if (kind_ != Kind::BASE) { + writer->String("kind"); + writer->Int(static_cast(kind_)); + } + if (joints_.joint().size() > 0) { + writer->String("joints"); + joints_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool JointFrame::IsNullJSONData() const { + return joints_.IsNullJSONData() && kind_ == Kind::BASE; +} + +void CartesianFrame::set_position_kind(Kind position_kind) { + position_kind_ = position_kind; +} +CartesianFrame::Kind CartesianFrame::position_kind() const { + return position_kind_; +} +CartesianFrame::Kind *CartesianFrame::mutable_position_kind() { + return &position_kind_; +} +void CartesianFrame::set_position(const Position &position) { + position_ = position; +} +const Position &CartesianFrame::position() const { return position_; } +Position *CartesianFrame::mutable_position() { return &position_; } +void CartesianFrame::set_rotation_kind(Kind rotation_kind) { + rotation_kind_ = rotation_kind; +} +CartesianFrame::Kind CartesianFrame::rotation_kind() const { + return rotation_kind_; +} +CartesianFrame::Kind *CartesianFrame::mutable_rotation_kind() { + return &rotation_kind_; +} +void CartesianFrame::set_rotation(const Rotation &rotation) { + rotation_ = rotation; +} +const Rotation &CartesianFrame::rotation() const { return rotation_; } +Rotation *CartesianFrame::mutable_rotation() { return &rotation_; } +bool CartesianFrame::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("position_kind")) { + position_kind_ = static_cast(obj["position_kind"].GetInt()); + } + if (obj.HasMember("position")) { + position_.Deserialize(obj["position"]); + } + if (obj.HasMember("rotation_kind")) { + rotation_kind_ = static_cast(obj["rotation_kind"].GetInt()); + } + if (obj.HasMember("rotation")) { + rotation_.Deserialize(obj["rotation"]); + } + return true; +} +bool CartesianFrame::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + if (position_kind_ != Kind::BASE) { + writer->String("position_kind"); + writer->Int(static_cast(position_kind_)); + } + if (!position_.IsNullJSONData()) { + writer->String("position"); + position_.Serialize(writer); + } + if (rotation_kind_ != Kind::BASE) { + writer->String("rotation_kind"); + writer->Int(static_cast(rotation_kind_)); + } + if (!rotation_.IsNullJSONData()) { + writer->String("rotation"); + rotation_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool CartesianFrame::IsNullJSONData() const { + return position_.IsNullJSONData() && rotation_.IsNullJSONData() && + position_kind_ == Kind::BASE && rotation_kind_ == Kind::BASE; +} + +void CartesianPose::set_position(const Position &position) { + position_ = position; +} +const Position &CartesianPose::position() const { return position_; } +Position *CartesianPose::mutable_position() { return &position_; } +void CartesianPose::set_rotation(const Rotation &rotation) { + rotation_ = rotation; +} +const Rotation &CartesianPose::rotation() const { return rotation_; } +Rotation *CartesianPose::mutable_rotation() { return &rotation_; } +bool CartesianPose::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("position")) { + position_.Deserialize(obj["position"]); + } + if (obj.HasMember("rotation")) { + rotation_.Deserialize(obj["rotation"]); + } + return true; +} +bool CartesianPose::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + if (!position_.IsNullJSONData()) { + writer->String("position"); + position_.Serialize(writer); + } + if (!rotation_.IsNullJSONData()) { + writer->String("rotation"); + rotation_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool CartesianPose::IsNullJSONData() const { + return position_.IsNullJSONData() && rotation_.IsNullJSONData(); +} + +// // JointTargetPose begin +// void JointTargetPose::set_base(const JointFrame &base) { base_ = base; } +// const JointFrame &JointTargetPose::base() const { return base_; } +// JointFrame *JointTargetPose::mutable_base() { return &base_; } +// void JointTargetPose::set_delta(const JointPose &joints) { delta_ = joints; } +// const JointPose &JointTargetPose::delta() const { return delta_; } +// JointPose *JointTargetPose::mutable_delta() { return &delta_; } +// bool JointTargetPose::Deserialize(const rapidjson::Value &obj) +// { +// if (obj.HasMember("base")) +// { +// base_.Deserialize(obj["base"]); +// } +// if (obj.HasMember("delta")) +// { +// delta_.Deserialize(obj["delta"]); +// } +// return true; +// } +// bool JointTargetPose::Serialize( +// rapidjson::Writer *writer) const +// { +// writer->StartObject(); +// if (!base_.IsNullJSONData()) +// { +// writer->String("base"); +// base_.Serialize(writer); +// } +// if (!delta_.IsNullJSONData()) +// { +// writer->String("delta"); +// delta_.Serialize(writer); +// } +// writer->EndObject(); +// return true; +// } +// bool JointTargetPose::IsNullJSONData() const +// { +// return base_.IsNullJSONData() && delta_.IsNullJSONData(); +// } +// // JointTargetPose end + +// // CartesianTargetPose begin +// void CartesianTargetPose::set_base(const CartesianFrame &base) { base_ = +// base; } const CartesianFrame &CartesianTargetPose::base() const { return +// base_; } CartesianFrame *CartesianTargetPose::mutable_base() { return &base_; +// } void CartesianTargetPose::set_delta(const CartesianPose &delta) +// { +// delta_ = delta; +// } +// const CartesianPose &CartesianTargetPose::delta() const { return delta_; } +// CartesianPose *CartesianTargetPose::mutable_delta() { return &delta_; } +// bool CartesianTargetPose::Deserialize(const rapidjson::Value &obj) +// { +// if (obj.HasMember("base")) +// { +// base_.Deserialize(obj["base"]); +// } +// if (obj.HasMember("delta")) +// { +// delta_.Deserialize(obj["delta"]); +// } +// return true; +// } +// bool CartesianTargetPose::Serialize( +// rapidjson::Writer *writer) const +// { +// writer->StartObject(); +// if (!base_.IsNullJSONData()) +// { +// writer->String("base"); +// base_.Serialize(writer); +// } +// if (!delta_.IsNullJSONData()) +// { +// writer->String("delta"); +// delta_.Serialize(writer); +// } +// writer->EndObject(); +// return true; +// } +// bool CartesianTargetPose::IsNullJSONData() const +// { +// return base_.IsNullJSONData() && delta_.IsNullJSONData(); +// } +// // CartesianTargetPose end + +// Pose begin +Pose &Pose::operator=(const Pose &other) { + kind_ = other.kind_; + joint_.reset(); + cart_.reset(); + cart_frame_index_.reset(); + cart_frame_.reset(); + if (kind_ == JOINT) { + joint_ = std::make_unique(); + *joint_ = *other.joint_; + } else { + cart_ = std::make_unique(); + *cart_ = *other.cart_; + cart_frame_index_ = std::make_unique(); + *cart_frame_index_ = *other.cart_frame_index_; + cart_frame_ = std::make_unique(); + *cart_frame_ = *other.cart_frame_; + } + return *this; +} +void Pose::set_kind(Kind kind) { + kind_ = kind; + joint_.reset(); + cart_.reset(); + cart_frame_index_.reset(); + cart_frame_.reset(); + if (kind_ == JOINT) { + joint_ = std::make_unique(); + } else { + cart_ = std::make_unique(); + cart_frame_index_ = std::make_unique(); + cart_frame_ = std::make_unique(); + } +} + +Pose::Kind Pose::kind() const { return kind_; } + +void Pose::set_joint(const JointPose &joint) { + kind_ = JOINT; + cart_.reset(); + cart_frame_index_.reset(); + cart_frame_.reset(); + joint_ = std::make_unique(joint); +} + +JointPose *Pose::mutable_joint() { + kind_ = JOINT; + cart_.reset(); + cart_frame_index_.reset(); + cart_frame_.reset(); + if (!joint_) { + joint_ = std::make_unique(); + } + return joint_.get(); +} + +void Pose::set_cart(const CartesianPose &cart) { + kind_ = CARTESIAN; + joint_.reset(); + cart_ = std::make_unique(cart); +} + +CartesianPose *Pose::mutable_cart() { + kind_ = CARTESIAN; + joint_.reset(); + if (!cart_) { + cart_ = std::make_unique(); + } + return cart_.get(); +} + +void Pose::set_cart_frame_index(const db::LoadRequest &cart_frame_index) { + kind_ = CARTESIAN; + joint_.reset(); + if (!cart_frame_index_) { + cart_frame_index_ = std::make_unique(cart_frame_index); + }; +} + +db::LoadRequest *Pose::mutable_cart_frame_index() { + kind_ = CARTESIAN; + joint_.reset(); + if (!cart_frame_index_) { + cart_frame_index_ = std::make_unique(); + } + return cart_frame_index_.get(); +} + +void Pose::set_cart_frame(const CartesianFrame &cart_frame) { + kind_ = CARTESIAN; + joint_.reset(); + if (!cart_frame_) { + cart_frame_ = std::make_unique(cart_frame); + } +} + +CartesianFrame *Pose::mutable_cart_frame() { + kind_ = CARTESIAN; + joint_.reset(); + if (!cart_frame_) { + cart_frame_ = std::make_unique(); + } + return cart_frame_.get(); +} + +bool Pose::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("kind")) { + kind_ = static_cast(obj["kind"].GetInt()); + } else { + return false; + } + if (kind_ == JOINT) { + if (obj.HasMember("joint")) { + if (!joint_) { joint_ = std::make_unique(); } - else - { - cart_ = std::make_unique(); - cart_frame_index_ = std::make_unique(); - cart_frame_ = std::make_unique(); - } - } - - Pose::Kind Pose::kind() const - { - return kind_; - } - - void Pose::set_joint(const JointPose &joint) - { - kind_ = JOINT; cart_.reset(); cart_frame_index_.reset(); cart_frame_.reset(); - joint_ = std::make_unique(joint); + joint_->Deserialize(obj["joint"]); } - - JointPose *Pose::mutable_joint() - { - kind_ = JOINT; - cart_.reset(); - cart_frame_index_.reset(); - cart_frame_.reset(); - if (!joint_) - { - joint_ = std::make_unique(); - } - return joint_.get(); - } - - void Pose::set_cart(const CartesianPose &cart) - { - kind_ = CARTESIAN; - joint_.reset(); - cart_ = std::make_unique(cart); - } - - CartesianPose *Pose::mutable_cart() - { - kind_ = CARTESIAN; - joint_.reset(); - if (!cart_) - { + } else { + joint_.reset(); + if (obj.HasMember("cart")) { + if (!cart_) { cart_ = std::make_unique(); } - return cart_.get(); + cart_->Deserialize(obj["cart"]); + } else { + return false; } - - void Pose::set_cart_frame_index(const db::LoadRequest &cart_frame_index) - { - kind_ = CARTESIAN; - joint_.reset(); - if (!cart_frame_index_) - { - cart_frame_index_ = std::make_unique(cart_frame_index); - }; - } - - db::LoadRequest *Pose::mutable_cart_frame_index() - { - kind_ = CARTESIAN; - joint_.reset(); - if (!cart_frame_index_) - { + if (obj.HasMember("cart_frame_index")) { + if (!cart_frame_index_) { cart_frame_index_ = std::make_unique(); } - return cart_frame_index_.get(); - } - - void Pose::set_cart_frame(const CartesianFrame &cart_frame) - { - kind_ = CARTESIAN; - joint_.reset(); - if (!cart_frame_) - { - cart_frame_ = std::make_unique(cart_frame); - } + cart_frame_index_->Deserialize(obj["cart_frame_index"]); } - - CartesianFrame *Pose::mutable_cart_frame() - { - kind_ = CARTESIAN; - joint_.reset(); - if (!cart_frame_) - { + if (obj.HasMember("cart_frame")) { + if (!cart_frame_) { cart_frame_ = std::make_unique(); } - return cart_frame_.get(); - } - - bool Pose::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("kind")) - { - kind_ = static_cast(obj["kind"].GetInt()); - } - else - { - return false; - } - if(kind_ == JOINT) - { - if (obj.HasMember("joint")) - { - if (!joint_) - { - joint_ = std::make_unique(); - } - cart_.reset(); - cart_frame_index_.reset(); - cart_frame_.reset(); - joint_->Deserialize(obj["joint"]); - } - } - else - { - joint_.reset(); - if (obj.HasMember("cart")) - { - if (!cart_) - { - cart_ = std::make_unique(); - } - cart_->Deserialize(obj["cart"]); - } - else - { - return false; - } - if (obj.HasMember("cart_frame_index")) - { - if (!cart_frame_index_) - { - cart_frame_index_ = std::make_unique(); - } - cart_frame_index_->Deserialize(obj["cart_frame_index"]); - } - if (obj.HasMember("cart_frame")) - { - if (!cart_frame_) - { - cart_frame_ = std::make_unique(); - } - cart_frame_->Deserialize(obj["cart_frame"]); - } - } - return true; - } - - bool Pose::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("kind"); - writer->Int(static_cast(kind_)); - if(kind_ == JOINT) - { - if (joint_) - { - writer->String("joint"); - joint_->Serialize(writer); - } - } - else - { - if (cart_) - { - writer->String("cart"); - cart_->Serialize(writer); - } - if (cart_frame_index_) - { - writer->String("cart_frame_index"); - cart_frame_index_->Serialize(writer); - } - if (cart_frame_) - { - writer->String("cart_frame"); - cart_frame_->Serialize(writer); - } - } - writer->EndObject(); - return true; - } - bool Pose::IsNullJSONData() const - { - if(joint_ || cart_ || cart_frame_index_ || cart_frame_) - { - return false; - } - return true; - } - // Pose end - - // PoseRequest begin - void PoseRequest::set_pose(const Pose &pose) { pose_ = pose; } - const Pose &PoseRequest::pose() const { return pose_; } - Pose *PoseRequest::mutable_pose() { return &pose_; } - bool PoseRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("pose")) - { - pose_.Deserialize(obj["pose"]); - } - return true; - } - bool PoseRequest::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - if (!pose_.IsNullJSONData()) - { - writer->String("pose"); - pose_.Serialize(writer); - } - writer->EndObject(); - return true; + cart_frame_->Deserialize(obj["cart_frame"]); } - bool PoseRequest::IsNullJSONData() const { return pose_.IsNullJSONData(); } - - void GetInverseKinRequest::set_pose(const Pose &pose) { pose_ = pose; } - const Pose &GetInverseKinRequest::pose() const { return pose_; } - Pose *GetInverseKinRequest::mutable_pose() { return &pose_; } - - void GetInverseKinRequest::set_refer(const JointPose& refer) - { - if(!refer_) - { - refer_ = std::make_unique(); - } - *refer_ = refer; - } - const JointPose* GetInverseKinRequest::refer() const { - if(!refer_) - { - return nullptr; - } - return refer_.get(); - } - JointPose* GetInverseKinRequest::mutable_refer() { - if(!refer_) - { - refer_ = std::make_unique(); - } - return refer_.get(); - } - bool GetInverseKinRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("pose")) - { - pose_.Deserialize(obj["pose"]); - } - if (obj.HasMember("refer")) - { - if(!refer_) - { - refer_ = std::make_unique(); - } - refer_->Deserialize(obj["refer"]); - } - return true; - } - bool GetInverseKinRequest::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - if (!pose_.IsNullJSONData()) - { - writer->String("pose"); - pose_.Serialize(writer); - } - if(refer_ && !refer_->IsNullJSONData()) - { - writer->String("refer"); - refer_->Serialize(writer); - } - writer->EndObject(); - return true; - } - bool GetInverseKinRequest::IsNullJSONData() const { return false; } - - void GetPoseTransRequest::set_from(const Pose &from) { from_ = from; } - const Pose &GetPoseTransRequest::from() const { return from_; } - Pose *GetPoseTransRequest::mutable_from() { return &from_; } - - void GetPoseTransRequest::set_from_to(const Pose &from_to){ from_to_ = from_to; } - const Pose &GetPoseTransRequest::from_to() const { return from_to_; } - Pose *GetPoseTransRequest::mutable_from_to() { return &from_to_; } + } + return true; +} - bool GetPoseTransRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("from")) - { - from_.Deserialize(obj["from"]); - } - if (obj.HasMember("from_to")) - { - from_to_.Deserialize(obj["from_to"]); - } - return true; - } - bool GetPoseTransRequest::Serialize( - rapidjson::Writer *writer) const - { - writer->StartObject(); - if (!from_.IsNullJSONData()) - { - writer->String("from"); - from_.Serialize(writer); - } - if (!from_to_.IsNullJSONData()) - { - writer->String("from_to"); - from_to_.Serialize(writer); - } - writer->EndObject(); - return true; - } - bool GetPoseTransRequest::IsNullJSONData() const { return false; } - } // namespace posture - -} // namespace lebai \ No newline at end of file +bool Pose::Serialize(rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("kind"); + writer->Int(static_cast(kind_)); + if (kind_ == JOINT) { + if (joint_) { + writer->String("joint"); + joint_->Serialize(writer); + } + } else { + if (cart_) { + writer->String("cart"); + cart_->Serialize(writer); + } + if (cart_frame_index_) { + writer->String("cart_frame_index"); + cart_frame_index_->Serialize(writer); + } + if (cart_frame_) { + writer->String("cart_frame"); + cart_frame_->Serialize(writer); + } + } + writer->EndObject(); + return true; +} +bool Pose::IsNullJSONData() const { + if (joint_ || cart_ || cart_frame_index_ || cart_frame_) { + return false; + } + return true; +} +// Pose end + +// PoseRequest begin +void PoseRequest::set_pose(const Pose &pose) { pose_ = pose; } +const Pose &PoseRequest::pose() const { return pose_; } +Pose *PoseRequest::mutable_pose() { return &pose_; } +bool PoseRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("pose")) { + pose_.Deserialize(obj["pose"]); + } + return true; +} +bool PoseRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + if (!pose_.IsNullJSONData()) { + writer->String("pose"); + pose_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool PoseRequest::IsNullJSONData() const { return pose_.IsNullJSONData(); } + +void GetInverseKinRequest::set_pose(const Pose &pose) { pose_ = pose; } +const Pose &GetInverseKinRequest::pose() const { return pose_; } +Pose *GetInverseKinRequest::mutable_pose() { return &pose_; } + +void GetInverseKinRequest::set_refer(const JointPose &refer) { + if (!refer_) { + refer_ = std::make_unique(); + } + *refer_ = refer; +} +const JointPose *GetInverseKinRequest::refer() const { + if (!refer_) { + return nullptr; + } + return refer_.get(); +} +JointPose *GetInverseKinRequest::mutable_refer() { + if (!refer_) { + refer_ = std::make_unique(); + } + return refer_.get(); +} +bool GetInverseKinRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("pose")) { + pose_.Deserialize(obj["pose"]); + } + if (obj.HasMember("refer")) { + if (!refer_) { + refer_ = std::make_unique(); + } + refer_->Deserialize(obj["refer"]); + } + return true; +} +bool GetInverseKinRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + if (!pose_.IsNullJSONData()) { + writer->String("pose"); + pose_.Serialize(writer); + } + if (refer_ && !refer_->IsNullJSONData()) { + writer->String("refer"); + refer_->Serialize(writer); + } + writer->EndObject(); + return true; +} +bool GetInverseKinRequest::IsNullJSONData() const { return false; } + +void GetPoseTransRequest::set_from(const Pose &from) { from_ = from; } +const Pose &GetPoseTransRequest::from() const { return from_; } +Pose *GetPoseTransRequest::mutable_from() { return &from_; } + +void GetPoseTransRequest::set_from_to(const Pose &from_to) { + from_to_ = from_to; +} +const Pose &GetPoseTransRequest::from_to() const { return from_to_; } +Pose *GetPoseTransRequest::mutable_from_to() { return &from_to_; } + +bool GetPoseTransRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("from")) { + from_.Deserialize(obj["from"]); + } + if (obj.HasMember("from_to")) { + from_to_.Deserialize(obj["from_to"]); + } + return true; +} +bool GetPoseTransRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + if (!from_.IsNullJSONData()) { + writer->String("from"); + from_.Serialize(writer); + } + if (!from_to_.IsNullJSONData()) { + writer->String("from_to"); + from_to_.Serialize(writer); + } + writer->EndObject(); + return true; +} +bool GetPoseTransRequest::IsNullJSONData() const { return false; } +} // namespace posture + +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/posture.hh b/sdk/src/protos/posture.hh index 0062214..9e84070 100755 --- a/sdk/src/protos/posture.hh +++ b/sdk/src/protos/posture.hh @@ -110,9 +110,10 @@ class RotationMatrix : public JSONBase { std::array* mutable_data(); protected: - std::array data_ = {{1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0}};; /*!< Rotation matrix data */ - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. + std::array data_ = {{1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0}}; + ; /*!< Rotation matrix data */ + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. public: virtual bool Deserialize(const rapidjson::Value& obj); virtual bool Serialize( @@ -292,26 +293,23 @@ class Pose : public JSONBase { Kind kind() const; void set_joint(const JointPose& joint); - JointPose* mutable_joint(); - + JointPose* mutable_joint(); + void set_cart(const CartesianPose& cartesian_pose); CartesianPose* mutable_cart(); - + void set_cart_frame_index(const db::LoadRequest& cart_frame_index); db::LoadRequest* mutable_cart_frame_index(); - + void set_cart_frame(const CartesianFrame& cart_frame); CartesianFrame* mutable_cart_frame(); - - protected: Kind kind_; std::unique_ptr joint_ = nullptr; std::unique_ptr cart_ = nullptr; std::unique_ptr cart_frame_index_ = nullptr; std::unique_ptr cart_frame_ = nullptr; - public: // These methods are used to serialize and deserialize the class. @@ -341,7 +339,7 @@ class PoseRequest : public JSONBase { }; class GetInverseKinRequest : public JSONBase { -public: + public: // Data // pose void set_pose(const Pose& pose); @@ -350,21 +348,20 @@ public: // refer void set_refer(const JointPose& refer); - const JointPose * refer() const; - JointPose * mutable_refer(); + const JointPose* refer() const; + JointPose* mutable_refer(); protected: Pose pose_; std::unique_ptr refer_; - public: // These methods are used to serialize and deserialize the class. // They will not be wrapped in the SDK. virtual bool Deserialize(const rapidjson::Value& obj); virtual bool Serialize( rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; + virtual bool IsNullJSONData() const; }; class GetPoseTransRequest : public JSONBase { @@ -377,7 +374,7 @@ class GetPoseTransRequest : public JSONBase { // from_to void set_from_to(const Pose& refer); - const Pose & from_to() const; + const Pose& from_to() const; Pose* mutable_from_to(); protected: diff --git a/sdk/src/protos/safety.hh b/sdk/src/protos/safety.hh index c57f0c5..ed0fbb2 100644 --- a/sdk/src/protos/safety.hh +++ b/sdk/src/protos/safety.hh @@ -4,23 +4,22 @@ #include #include -namespace lebai -{ - namespace safety - { - class CollisionTorqueDiff : public JSONBase - { - public: - void set_diffs(std::vector diffs); - std::vector diffs(); - std::vector * mutable_diffs(); +namespace lebai { +namespace safety { +class CollisionTorqueDiff : public JSONBase { + public: + void set_diffs(std::vector diffs); + std::vector diffs(); + std::vector *mutable_diffs(); - protected: - std::vector diffs_; - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file + protected: + std::vector diffs_; + + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace safety +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/serial.cc b/sdk/src/protos/serial.cc index 0799e7e..f07baa1 100644 --- a/sdk/src/protos/serial.cc +++ b/sdk/src/protos/serial.cc @@ -1,116 +1,74 @@ #include #include "serial.hh" -namespace lebai -{ - namespace serial - { - void SetSerialBaudRateRequest::set_device(std::string device) - { - device_ = device; - } - std::string SetSerialBaudRateRequest::device() const - { - return device_; - } - std::string *SetSerialBaudRateRequest::mutable_device() - { - return &device_; - } +namespace lebai { +namespace serial { +void SetSerialBaudRateRequest::set_device(std::string device) { + device_ = device; +} +std::string SetSerialBaudRateRequest::device() const { return device_; } +std::string *SetSerialBaudRateRequest::mutable_device() { return &device_; } - void SetSerialBaudRateRequest::set_baud_rate(unsigned int baud_rate) - { - baud_rate_ = baud_rate; - } - unsigned int SetSerialBaudRateRequest::baud_rate() const - { - return baud_rate_; - } - unsigned int *SetSerialBaudRateRequest::mutable_baud_rate() - { - return &baud_rate_; - } +void SetSerialBaudRateRequest::set_baud_rate(unsigned int baud_rate) { + baud_rate_ = baud_rate; +} +unsigned int SetSerialBaudRateRequest::baud_rate() const { return baud_rate_; } +unsigned int *SetSerialBaudRateRequest::mutable_baud_rate() { + return &baud_rate_; +} - bool SetSerialBaudRateRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if (obj.HasMember("baud_rate")) - { - baud_rate_ = obj["baud_rate"].GetUint(); - } - return true; - } - bool SetSerialBaudRateRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("baud_rate"); - writer->Uint(baud_rate_); - writer->EndObject(); - return true; - } - bool SetSerialBaudRateRequest::IsNullJSONData() const - { - return false; - } +bool SetSerialBaudRateRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("baud_rate")) { + baud_rate_ = obj["baud_rate"].GetUint(); + } + return true; +} +bool SetSerialBaudRateRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("baud_rate"); + writer->Uint(baud_rate_); + writer->EndObject(); + return true; +} +bool SetSerialBaudRateRequest::IsNullJSONData() const { return false; } - void SetSerialParityRequest::set_device(std::string device) - { - device_ = device; - } - std::string SetSerialParityRequest::device() const - { - return device_; - } - std::string *SetSerialParityRequest::mutable_device() - { - return &device_; - } +void SetSerialParityRequest::set_device(std::string device) { + device_ = device; +} +std::string SetSerialParityRequest::device() const { return device_; } +std::string *SetSerialParityRequest::mutable_device() { return &device_; } - void SetSerialParityRequest::set_parity(Parity parity) - { - parity_ = parity; - } - Parity SetSerialParityRequest::parity() const - { - return parity_; - } - Parity *SetSerialParityRequest::mutable_parity() - { - return &parity_; - } +void SetSerialParityRequest::set_parity(Parity parity) { parity_ = parity; } +Parity SetSerialParityRequest::parity() const { return parity_; } +Parity *SetSerialParityRequest::mutable_parity() { return &parity_; } - bool SetSerialParityRequest::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("device")) - { - std::string device_str = std::string(obj["device"].GetString()); - device_ = device_str; - } - if (obj.HasMember("parity")) - { - parity_ = static_cast(obj["parity"].GetUint()); - } - return true; - } - bool SetSerialParityRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("device"); - writer->String(device_.c_str()); - writer->Key("parity"); - writer->Uint(static_cast(parity_)); - writer->EndObject(); - return true; - } - bool SetSerialParityRequest::IsNullJSONData() const - { - return false; - } - } -} \ No newline at end of file +bool SetSerialParityRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("device")) { + std::string device_str = std::string(obj["device"].GetString()); + device_ = device_str; + } + if (obj.HasMember("parity")) { + parity_ = static_cast(obj["parity"].GetUint()); + } + return true; +} +bool SetSerialParityRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("device"); + writer->String(device_.c_str()); + writer->Key("parity"); + writer->Uint(static_cast(parity_)); + writer->EndObject(); + return true; +} +bool SetSerialParityRequest::IsNullJSONData() const { return false; } +} // namespace serial +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/serial.hh b/sdk/src/protos/serial.hh index 00e0925..6b8db42 100644 --- a/sdk/src/protos/serial.hh +++ b/sdk/src/protos/serial.hh @@ -4,59 +4,56 @@ #include #include -namespace lebai -{ - namespace serial - { - class SetSerialBaudRateRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_baud_rate(unsigned int baud_rate); - unsigned int baud_rate() const; - unsigned int *mutable_baud_rate(); - - protected: - std::string device_; - unsigned int baud_rate_ = 115200; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - - enum Parity - { - None = 0, - Odd = 1, - Even = 2, - }; - - class SetSerialParityRequest : public JSONBase - { - public: - void set_device(std::string device); - std::string device() const; - std::string *mutable_device(); - - void set_parity(Parity parity); - Parity parity() const; - Parity *mutable_parity(); - - protected: - std::string device_; - Parity parity_ = Parity::None; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file +namespace lebai { +namespace serial { +class SetSerialBaudRateRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_baud_rate(unsigned int baud_rate); + unsigned int baud_rate() const; + unsigned int *mutable_baud_rate(); + + protected: + std::string device_; + unsigned int baud_rate_ = 115200; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; + +enum Parity { + None = 0, + Odd = 1, + Even = 2, +}; + +class SetSerialParityRequest : public JSONBase { + public: + void set_device(std::string device); + std::string device() const; + std::string *mutable_device(); + + void set_parity(Parity parity); + Parity parity() const; + Parity *mutable_parity(); + + protected: + std::string device_; + Parity parity_ = Parity::None; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace serial +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/signal.cc b/sdk/src/protos/signal.cc index ba387e5..27c74d7 100644 --- a/sdk/src/protos/signal.cc +++ b/sdk/src/protos/signal.cc @@ -1,127 +1,75 @@ #include #include "signal.hh" -namespace lebai -{ - namespace signal - { - void SetSignalRequest::set_key(unsigned int key) - { - key_ = key; - } - unsigned int SetSignalRequest::key() const - { - return key_; - } - unsigned int * SetSignalRequest::mutable_key() - { - return &key_; - } - void SetSignalRequest::set_value(int value) - { - value_ = value; - } - int SetSignalRequest::value() const{ - return value_; - } - int * SetSignalRequest::mutable_value(){ - return &value_; - } - bool SetSignalRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("key")) - { - unsigned int key_int = (unsigned int)(obj["key"].GetUint()); - key_ = key_int; - } - if(obj.HasMember("value")) - { - int value_int = int(obj["value"].GetInt()); - value_ = value_int; - } - return true; - } - bool SetSignalRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("key"); - writer->Uint(key_); - writer->Key("value"); - writer->Int(value_); - writer->EndObject(); - return true; - } - bool SetSignalRequest::IsNullJSONData() const - { - return false; - } +namespace lebai { +namespace signal { +void SetSignalRequest::set_key(unsigned int key) { key_ = key; } +unsigned int SetSignalRequest::key() const { return key_; } +unsigned int *SetSignalRequest::mutable_key() { return &key_; } +void SetSignalRequest::set_value(int value) { value_ = value; } +int SetSignalRequest::value() const { return value_; } +int *SetSignalRequest::mutable_value() { return &value_; } +bool SetSignalRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("key")) { + unsigned int key_int = (unsigned int)(obj["key"].GetUint()); + key_ = key_int; + } + if (obj.HasMember("value")) { + int value_int = int(obj["value"].GetInt()); + value_ = value_int; + } + return true; +} +bool SetSignalRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("key"); + writer->Uint(key_); + writer->Key("value"); + writer->Int(value_); + writer->EndObject(); + return true; +} +bool SetSignalRequest::IsNullJSONData() const { return false; } - void GetSignalRequest::set_key(unsigned int key) - { - key_ = key; - } - unsigned int GetSignalRequest::key() const - { - return key_; - } - unsigned int * GetSignalRequest::mutable_key() - { - return &key_; - } - bool GetSignalRequest::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("key")) - { - unsigned int key_int = (unsigned int)(obj["key"].GetUint()); - key_ = key_int; - } - return true; - } - bool GetSignalRequest::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("key"); - writer->Uint(key_); - writer->EndObject(); - return true; - } - bool GetSignalRequest::IsNullJSONData() const - { - return false; - } +void GetSignalRequest::set_key(unsigned int key) { key_ = key; } +unsigned int GetSignalRequest::key() const { return key_; } +unsigned int *GetSignalRequest::mutable_key() { return &key_; } +bool GetSignalRequest::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("key")) { + unsigned int key_int = (unsigned int)(obj["key"].GetUint()); + key_ = key_int; + } + return true; +} +bool GetSignalRequest::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("key"); + writer->Uint(key_); + writer->EndObject(); + return true; +} +bool GetSignalRequest::IsNullJSONData() const { return false; } - void GetSignalResponse::set_value(int value) - { - value_ = value; - } - int GetSignalResponse::value() const - { - return value_; - } - int * GetSignalResponse::mutable_value() - { - return &value_; - } - bool GetSignalResponse::Deserialize(const rapidjson::Value &obj) - { - if(obj.HasMember("value")) - { - int value_int = int(obj["value"].GetInt()); - value_ = value_int; - } - return true; - } - bool GetSignalResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("value"); - writer->Int(value_); - writer->EndObject(); - return true; - } - bool GetSignalResponse::IsNullJSONData() const - { - return false; - } - } -} \ No newline at end of file +void GetSignalResponse::set_value(int value) { value_ = value; } +int GetSignalResponse::value() const { return value_; } +int *GetSignalResponse::mutable_value() { return &value_; } +bool GetSignalResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("value")) { + int value_int = int(obj["value"].GetInt()); + value_ = value_int; + } + return true; +} +bool GetSignalResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("value"); + writer->Int(value_); + writer->EndObject(); + return true; +} +bool GetSignalResponse::IsNullJSONData() const { return false; } +} // namespace signal +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/signal.hh b/sdk/src/protos/signal.hh index b478210..a7d497e 100644 --- a/sdk/src/protos/signal.hh +++ b/sdk/src/protos/signal.hh @@ -6,65 +6,63 @@ #include #include -namespace lebai -{ - namespace signal - { - class SetSignalRequest : public JSONBase - { - public: - void set_key(unsigned int key); - unsigned int key() const; - unsigned int * mutable_key(); +namespace lebai { +namespace signal { +class SetSignalRequest : public JSONBase { + public: + void set_key(unsigned int key); + unsigned int key() const; + unsigned int *mutable_key(); - void set_value(int value); - int value() const; - int * mutable_value(); + void set_value(int value); + int value() const; + int *mutable_value(); - protected: - unsigned int key_; - int value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; + protected: + unsigned int key_; + int value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - class GetSignalRequest : public JSONBase - { - public: - void set_key(unsigned int key); - unsigned int key() const; - unsigned int * mutable_key(); +class GetSignalRequest : public JSONBase { + public: + void set_key(unsigned int key); + unsigned int key() const; + unsigned int *mutable_key(); - protected: - unsigned int key_; - int value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; + protected: + unsigned int key_; + int value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; - class GetSignalResponse : public JSONBase - { - public: - void set_value(int value); - int value() const; - int * mutable_value(); +class GetSignalResponse : public JSONBase { + public: + void set_value(int value); + int value() const; + int *mutable_value(); - protected: - int value_; - // These methods are used to serialize and deserialize the class. - // They will not be wrapped in the SDK. - public: - virtual bool Deserialize(const rapidjson::Value &obj); - virtual bool Serialize(rapidjson::Writer *writer) const; - virtual bool IsNullJSONData() const; - }; - } -} \ No newline at end of file + protected: + int value_; + // These methods are used to serialize and deserialize the class. + // They will not be wrapped in the SDK. + public: + virtual bool Deserialize(const rapidjson::Value &obj); + virtual bool Serialize( + rapidjson::Writer *writer) const; + virtual bool IsNullJSONData() const; +}; +} // namespace signal +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/system.cc b/sdk/src/protos/system.cc index ae3da03..2179f00 100755 --- a/sdk/src/protos/system.cc +++ b/sdk/src/protos/system.cc @@ -2,316 +2,197 @@ #include #include "system.hh" -namespace lebai -{ - namespace system - { - void GetRobotStateResponse::set_state(RobotState state) - { - state_ = state; - } - const RobotState &GetRobotStateResponse::state() const - { - return state_; - } - RobotState *GetRobotStateResponse::mutable_state() - { - return &state_; - } - bool GetRobotStateResponse::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("state")) - { - std::string state_str = std::string(obj["state"].GetString()); - if (state_str == "ERROR") - { - state_ = ERROR; - } - else if (state_str == "DISCONNECTED") - { - state_ = DISCONNECTED; - } - else if (state_str == "ESTOP") - { - state_ = ESTOP; - } - else if (state_str == "BOOTING") - { - state_ = BOOTING; - } - else if (state_str == "ROBOT_OFF") - { - state_ = ROBOT_OFF; - } - else if (state_str == "ROBOT_ON") - { - state_ = ROBOT_ON; - } - else if (state_str == "IDLE") - { - state_ = IDLE; - } - else if (state_str == "PAUSED") - { - state_ = PAUSED; - } - else if (state_str == "MOVING") - { - state_ = MOVING; - } - else if (state_str == "UPDATING") - { - state_ = UPDATING; - } - else if (state_str == "STOPPING") - { - state_ = STOPPING; - } - else if (state_str == "TEACHING") - { - state_ = TEACHING; - } - else if (state_str == "STOP") - { - state_ = STOP; - } - return true; - } - return false; - } - bool GetRobotStateResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("state"); - writer->Int(state_); - writer->EndObject(); - return true; - } - bool GetRobotStateResponse::IsNullJSONData() const - { - return false; - } +namespace lebai { +namespace system { +void GetRobotStateResponse::set_state(RobotState state) { state_ = state; } +const RobotState &GetRobotStateResponse::state() const { return state_; } +RobotState *GetRobotStateResponse::mutable_state() { return &state_; } +bool GetRobotStateResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("state")) { + std::string state_str = std::string(obj["state"].GetString()); + if (state_str == "ERROR") { + state_ = ERROR; + } else if (state_str == "DISCONNECTED") { + state_ = DISCONNECTED; + } else if (state_str == "ESTOP") { + state_ = ESTOP; + } else if (state_str == "BOOTING") { + state_ = BOOTING; + } else if (state_str == "ROBOT_OFF") { + state_ = ROBOT_OFF; + } else if (state_str == "ROBOT_ON") { + state_ = ROBOT_ON; + } else if (state_str == "IDLE") { + state_ = IDLE; + } else if (state_str == "PAUSED") { + state_ = PAUSED; + } else if (state_str == "MOVING") { + state_ = MOVING; + } else if (state_str == "UPDATING") { + state_ = UPDATING; + } else if (state_str == "STOPPING") { + state_ = STOPPING; + } else if (state_str == "TEACHING") { + state_ = TEACHING; + } else if (state_str == "STOP") { + state_ = STOP; + } + return true; + } + return false; +} +bool GetRobotStateResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("state"); + writer->Int(state_); + writer->EndObject(); + return true; +} +bool GetRobotStateResponse::IsNullJSONData() const { return false; } - void SystemInfo::set_name(const std::string &name) - { - name_ = name; - } - const std::string &SystemInfo::name() const - { - return name_; - } +void SystemInfo::set_name(const std::string &name) { name_ = name; } +const std::string &SystemInfo::name() const { return name_; } - std::string *SystemInfo::mutable_name() - { - return &name_; - } - // kernel_version string - void SystemInfo::set_kernel_version(const std::string &kernel_version) - { - kernel_version_ = kernel_version; - } - const std::string &SystemInfo::kernel_version() const - { - return kernel_version_; - } - std::string *SystemInfo::mutable_kernel_version() - { - return &kernel_version_; - } +std::string *SystemInfo::mutable_name() { return &name_; } +// kernel_version string +void SystemInfo::set_kernel_version(const std::string &kernel_version) { + kernel_version_ = kernel_version; +} +const std::string &SystemInfo::kernel_version() const { + return kernel_version_; +} +std::string *SystemInfo::mutable_kernel_version() { return &kernel_version_; } - bool SystemInfo::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("name")) - { - name_ = obj["name"].GetString(); - } - if (obj.HasMember("kernel_version")) - { - kernel_version_ = obj["kernel_version"].GetString(); - } - return true; - } +bool SystemInfo::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("name")) { + name_ = obj["name"].GetString(); + } + if (obj.HasMember("kernel_version")) { + kernel_version_ = obj["kernel_version"].GetString(); + } + return true; +} - bool SystemInfo::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("kind"); - writer->String(name_.c_str()); - writer->String("kernel_version"); - writer->String(kernel_version_.c_str()); - writer->EndObject(); - return true; - } - bool SystemInfo::IsNullJSONData() const - { - return false; - } +bool SystemInfo::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("kind"); + writer->String(name_.c_str()); + writer->String("kernel_version"); + writer->String(kernel_version_.c_str()); + writer->EndObject(); + return true; +} +bool SystemInfo::IsNullJSONData() const { return false; } - void PhyData::set_joint_temp(const std::vector &joint_temp) - { - joint_temp_ = joint_temp; - } - const std::vector &PhyData::joint_temp() const - { - return joint_temp_; - } - std::vector *PhyData::mutable_joint_temp() - { - return &joint_temp_; +void PhyData::set_joint_temp(const std::vector &joint_temp) { + joint_temp_ = joint_temp; +} +const std::vector &PhyData::joint_temp() const { return joint_temp_; } +std::vector *PhyData::mutable_joint_temp() { return &joint_temp_; } +void PhyData::set_joint_voltage(const std::vector &joint_voltage) { + joint_voltage_ = joint_voltage; +} +const std::vector &PhyData::joint_voltage() const { + return joint_voltage_; +} +std::vector *PhyData::mutable_joint_voltage() { + return &joint_voltage_; +} +// flange_voltage_ +void PhyData::set_flange_voltage(double flange_voltage) { + flange_voltage_ = flange_voltage; +} +double PhyData::flange_voltage() const { return flange_voltage_; } +double *PhyData::mutable_flange_voltage() { return &flange_voltage_; } +bool PhyData::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("joint_temp")) { + joint_temp_.clear(); + for (auto iter = obj["joint_temp"].GetArray().Begin(); + iter != obj["joint_temp"].GetArray().End(); iter++) { + joint_temp_.push_back(iter->GetDouble()); } - void PhyData::set_joint_voltage(const std::vector &joint_voltage) - { - joint_voltage_ = joint_voltage; - } - const std::vector &PhyData::joint_voltage() const - { - return joint_voltage_; - } - std::vector *PhyData::mutable_joint_voltage() - { - return &joint_voltage_; - } - // flange_voltage_ - void PhyData::set_flange_voltage(double flange_voltage) - { - flange_voltage_ = flange_voltage; - } - double PhyData::flange_voltage() const - { - return flange_voltage_; - } - double *PhyData::mutable_flange_voltage() - { - return &flange_voltage_; - } - bool PhyData::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("joint_temp")) - { - joint_temp_.clear(); - for (auto iter = obj["joint_temp"].GetArray().Begin(); iter != obj["joint_temp"].GetArray().End(); iter++) - { - joint_temp_.push_back(iter->GetDouble()); - } - } - if (obj.HasMember("joint_voltage")) - { - joint_voltage_.clear(); - for (auto iter = obj["joint_voltage"].GetArray().Begin(); iter != obj["joint_voltage"].GetArray().End(); iter++) - { - joint_voltage_.push_back(iter->GetDouble()); - } - } - if (obj.HasMember("flange_voltage")) - { - flange_voltage_ = obj["flange_voltage"].GetDouble(); - } - return true; + } + if (obj.HasMember("joint_voltage")) { + joint_voltage_.clear(); + for (auto iter = obj["joint_voltage"].GetArray().Begin(); + iter != obj["joint_voltage"].GetArray().End(); iter++) { + joint_voltage_.push_back(iter->GetDouble()); } + } + if (obj.HasMember("flange_voltage")) { + flange_voltage_ = obj["flange_voltage"].GetDouble(); + } + return true; +} - bool PhyData::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->String("joint_temp"); - writer->StartArray(); - for (auto iter = joint_temp_.begin(); iter != joint_temp_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->String("joint_voltage"); - writer->StartArray(); - for (auto iter = joint_voltage_.begin(); iter != joint_voltage_.end(); iter++) - { - writer->Double(*iter); - } - writer->EndArray(); - writer->String("flange_voltage"); - writer->Double(flange_voltage_); - writer->EndObject(); - return true; - } - bool PhyData::IsNullJSONData() const - { - return false; - } +bool PhyData::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->String("joint_temp"); + writer->StartArray(); + for (auto iter = joint_temp_.begin(); iter != joint_temp_.end(); iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->String("joint_voltage"); + writer->StartArray(); + for (auto iter = joint_voltage_.begin(); iter != joint_voltage_.end(); + iter++) { + writer->Double(*iter); + } + writer->EndArray(); + writer->String("flange_voltage"); + writer->Double(flange_voltage_); + writer->EndObject(); + return true; +} +bool PhyData::IsNullJSONData() const { return false; } - void GetEstopReasonResponse::set_reason(EstopReason reason) - { - reason_ = reason; - } - const EstopReason &GetEstopReasonResponse::reason() const - { - return reason_; - } - EstopReason *GetEstopReasonResponse::mutable_reason() - { - return &reason_; - } - bool GetEstopReasonResponse::Deserialize(const rapidjson::Value &obj) - { - if (obj.HasMember("reason")) - { - std::string reason_str = std::string(obj["reason"].GetString()); - if (reason_str == "NONE") - { - reason_ = NONE; - } - else if (reason_str == "SYSTEM") - { - reason_ = SYSTEM; - } - else if (reason_str == "MANUAL") - { - reason_ = MANUAL; - } - else if (reason_str == "HARD_ESTOP") - { - reason_ = HARD_ESTOP; - } - else if (reason_str == "COLLISION") - { - reason_ = COLLISION; - } - else if (reason_str == "JOINT_LIMIT") - { - reason_ = JOINT_LIMIT; - } - else if (reason_str == "EXCEED") - { - reason_ = EXCEED; - } - else if (reason_str == "TRAJECTORY_ERROR") - { - reason_ = TRAJECTORY_ERROR; - } - else if (reason_str == "COMM_ERROR") - { - reason_ = COMM_ERROR; - } - else if (reason_str == "CAN_ERROR") - { - reason_ = CAN_ERROR; - } - else if (reason_str == "JOINT_ERROR") - { - reason_ = JOINT_ERROR; - } - return true; - } - return false; - } - bool GetEstopReasonResponse::Serialize(rapidjson::Writer *writer) const - { - writer->StartObject(); - writer->Key("reason"); - writer->Int(reason_); - writer->EndObject(); - return true; - } - bool GetEstopReasonResponse::IsNullJSONData() const - { - return false; - } +void GetEstopReasonResponse::set_reason(EstopReason reason) { + reason_ = reason; +} +const EstopReason &GetEstopReasonResponse::reason() const { return reason_; } +EstopReason *GetEstopReasonResponse::mutable_reason() { return &reason_; } +bool GetEstopReasonResponse::Deserialize(const rapidjson::Value &obj) { + if (obj.HasMember("reason")) { + std::string reason_str = std::string(obj["reason"].GetString()); + if (reason_str == "NONE") { + reason_ = NONE; + } else if (reason_str == "SYSTEM") { + reason_ = SYSTEM; + } else if (reason_str == "MANUAL") { + reason_ = MANUAL; + } else if (reason_str == "HARD_ESTOP") { + reason_ = HARD_ESTOP; + } else if (reason_str == "COLLISION") { + reason_ = COLLISION; + } else if (reason_str == "JOINT_LIMIT") { + reason_ = JOINT_LIMIT; + } else if (reason_str == "EXCEED") { + reason_ = EXCEED; + } else if (reason_str == "TRAJECTORY_ERROR") { + reason_ = TRAJECTORY_ERROR; + } else if (reason_str == "COMM_ERROR") { + reason_ = COMM_ERROR; + } else if (reason_str == "CAN_ERROR") { + reason_ = CAN_ERROR; + } else if (reason_str == "JOINT_ERROR") { + reason_ = JOINT_ERROR; + } + return true; } -} \ No newline at end of file + return false; +} +bool GetEstopReasonResponse::Serialize( + rapidjson::Writer *writer) const { + writer->StartObject(); + writer->Key("reason"); + writer->Int(reason_); + writer->EndObject(); + return true; +} +bool GetEstopReasonResponse::IsNullJSONData() const { return false; } +} // namespace system +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/system.hh b/sdk/src/protos/system.hh index a65c208..e047e9a 100644 --- a/sdk/src/protos/system.hh +++ b/sdk/src/protos/system.hh @@ -6,129 +6,129 @@ #include #include -namespace lebai -{ - namespace system - { - enum RobotState - { - ERROR = -1, - DISCONNECTED = 0, - ESTOP = 1, - BOOTING = 2, - ROBOT_OFF = 3, - ROBOT_ON = 4, - IDLE = 5, - PAUSED = 6, - MOVING = 7, - UPDATING = 8, - STARTING = 9, - STOPPING = 10, - TEACHING = 11, - STOP = 12 - }; - class GetRobotStateResponse : public JSONBase - { - public: - void set_state(RobotState); - const RobotState & state() const; - RobotState * mutable_state(); - protected: - RobotState state_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; +namespace lebai { +namespace system { +enum RobotState { + ERROR = -1, + DISCONNECTED = 0, + ESTOP = 1, + BOOTING = 2, + ROBOT_OFF = 3, + ROBOT_ON = 4, + IDLE = 5, + PAUSED = 6, + MOVING = 7, + UPDATING = 8, + STARTING = 9, + STOPPING = 10, + TEACHING = 11, + STOP = 12 +}; +class GetRobotStateResponse : public JSONBase { + public: + void set_state(RobotState); + const RobotState& state() const; + RobotState* mutable_state(); + protected: + RobotState state_; - class SystemInfo : public JSONBase - { - public: - // class SystemInfoImpl; - // name string - void set_name(const std::string & name); - const std::string & name() const; - std::string * mutable_name(); - // kernel_version string - void set_kernel_version(const std::string & kernel_version); - const std::string & kernel_version() const; - std::string * mutable_kernel_version(); - // name string - // kernel_version string - // os_version string - // host_name string - // total_memory uint32 - // used_memory uint32 - // total_swap uint32 - // used_swap uint32 - // disks string repeated - // networks string repeated - // components string repeated - // processes string repeated + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; +class SystemInfo : public JSONBase { + public: + // class SystemInfoImpl; + // name string + void set_name(const std::string& name); + const std::string& name() const; + std::string* mutable_name(); + // kernel_version string + void set_kernel_version(const std::string& kernel_version); + const std::string& kernel_version() const; + std::string* mutable_kernel_version(); + // name string + // kernel_version string + // os_version string + // host_name string + // total_memory uint32 + // used_memory uint32 + // total_swap uint32 + // used_swap uint32 + // disks string repeated + // networks string repeated + // components string repeated + // processes string repeated - protected: - std::string name_; - std::string kernel_version_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; - class PhyData : public JSONBase - { - public: - // joint_temp_ - void set_joint_temp(const std::vector & joint_temp); - const std::vector & joint_temp() const; - std::vector * mutable_joint_temp(); - // joint_voltage - void set_joint_voltage(const std::vector & joint_temp); - const std::vector & joint_voltage() const; - std::vector * mutable_joint_voltage(); - // flange_voltage - void set_flange_voltage(double flange_voltage); - double flange_voltage() const; - double * mutable_flange_voltage(); + protected: + std::string name_; + std::string kernel_version_; - protected: - std::vector joint_temp_; - std::vector joint_voltage_; - double flange_voltage_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; +class PhyData : public JSONBase { + public: + // joint_temp_ + void set_joint_temp(const std::vector& joint_temp); + const std::vector& joint_temp() const; + std::vector* mutable_joint_temp(); + // joint_voltage + void set_joint_voltage(const std::vector& joint_temp); + const std::vector& joint_voltage() const; + std::vector* mutable_joint_voltage(); + // flange_voltage + void set_flange_voltage(double flange_voltage); + double flange_voltage() const; + double* mutable_flange_voltage(); - enum EstopReason - { - NONE = 0, - SYSTEM = 2, - MANUAL = 3, - HARD_ESTOP = 4, - COLLISION = 5, - JOINT_LIMIT = 6, - EXCEED = 7, - TRAJECTORY_ERROR = 8, - COMM_ERROR = 11, - CAN_ERROR = 12, - JOINT_ERROR = 13, - }; - class GetEstopReasonResponse : public JSONBase - { - public: - void set_reason(EstopReason); - const EstopReason & reason() const; - EstopReason * mutable_reason(); - protected: - EstopReason reason_; - public: - virtual bool Deserialize(const rapidjson::Value& obj); - virtual bool Serialize(rapidjson::Writer* writer) const; - virtual bool IsNullJSONData() const; - }; + protected: + std::vector joint_temp_; + std::vector joint_voltage_; + double flange_voltage_; - } -} // namespace lebai + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +enum EstopReason { + NONE = 0, + SYSTEM = 2, + MANUAL = 3, + HARD_ESTOP = 4, + COLLISION = 5, + JOINT_LIMIT = 6, + EXCEED = 7, + TRAJECTORY_ERROR = 8, + COMM_ERROR = 11, + CAN_ERROR = 12, + JOINT_ERROR = 13, +}; +class GetEstopReasonResponse : public JSONBase { + public: + void set_reason(EstopReason); + const EstopReason& reason() const; + EstopReason* mutable_reason(); + + protected: + EstopReason reason_; + + public: + virtual bool Deserialize(const rapidjson::Value& obj); + virtual bool Serialize( + rapidjson::Writer* writer) const; + virtual bool IsNullJSONData() const; +}; + +} // namespace system +} // namespace lebai diff --git a/sdk/src/protos/utils.cc b/sdk/src/protos/utils.cc index 7d57ea0..d49440a 100644 --- a/sdk/src/protos/utils.cc +++ b/sdk/src/protos/utils.cc @@ -1,31 +1,31 @@ #include "utils.hh" #include -namespace lebai -{ - std::string ToJSONRpcReqString(int id, const std::string & method, const JSONBase & data) - { - rapidjson::StringBuffer ss; - rapidjson::Writer writer(ss); // Can also use Writer for condensed formatting - writer.StartObject(); - writer.String("jsonrpc"); - writer.String("2.0"); - writer.String("method"); - writer.String(method.c_str()); - writer.String("params"); - writer.StartArray(); - data.Serialize(&writer); - writer.EndArray(); - writer.String("id"); - writer.Int(id); - writer.EndObject(); - return std::string(ss.GetString()); - } - std::string ToJSONRpcReqString(int id, const std::string & method, const std::string & data) - { - return std::string("{\"jsonrpc\":\"2.0\",\"method\":\"" +method + - "\",\"params\":["+data+"],\"id\":"+ std::to_string(id)+ "}"); - } - +namespace lebai { +std::string ToJSONRpcReqString(int id, const std::string &method, + const JSONBase &data) { + rapidjson::StringBuffer ss; + rapidjson::Writer writer( + ss); // Can also use Writer for condensed formatting + writer.StartObject(); + writer.String("jsonrpc"); + writer.String("2.0"); + writer.String("method"); + writer.String(method.c_str()); + writer.String("params"); + writer.StartArray(); + data.Serialize(&writer); + writer.EndArray(); + writer.String("id"); + writer.Int(id); + writer.EndObject(); + return std::string(ss.GetString()); +} +std::string ToJSONRpcReqString(int id, const std::string &method, + const std::string &data) { + return std::string("{\"jsonrpc\":\"2.0\",\"method\":\"" + method + + "\",\"params\":[" + data + + "],\"id\":" + std::to_string(id) + "}"); +} // int FromJSONRpcRespString(const std::string &s, JSONBase & data) // { @@ -56,53 +56,45 @@ namespace lebai // // return !doc.Parse(validJson.c_str()).HasParseError() ? true : false; - -// return true; +// return true; // } +JSONRpcRespParseResult ExtractJSONRpcRespString(const std::string &s, int &id, + int &error_code, + std::string &data) { + rapidjson::Document doc; + if (doc.Parse(s.c_str()).HasParseError()) { + return kInvalid; + } + if (!doc.HasMember("jsonrpc")) { + return kInvalid; + } + // std::string v = std::string(doc["jsonrpc"].GetString()); + if (std::string(doc["jsonrpc"].GetString()) != "2.0") { + // std::cout<<"ccc\n"; + return kInvalid; + } + if (!doc.HasMember("id")) { + return kInvalid; + } + id = doc["id"].GetInt(); - JSONRpcRespParseResult ExtractJSONRpcRespString(const std::string &s, int & id, int & error_code, std::string & data) - { - rapidjson::Document doc; - if(doc.Parse(s.c_str()).HasParseError()) - { - return kInvalid; - } - if(!doc.HasMember("jsonrpc")) - { - return kInvalid; - } - // std::string v = std::string(doc["jsonrpc"].GetString()); - if(std::string(doc["jsonrpc"].GetString()) != "2.0") - { - // std::cout<<"ccc\n"; - return kInvalid; - } - if(!doc.HasMember("id")) - { - return kInvalid; - } - id = doc["id"].GetInt(); - - if(doc.HasMember("error")) - { - // Error code and message. - error_code = doc["error"]["code"].GetInt(); - data = doc["error"]["message"].GetString(); - // std::cout << "Error: " << error_id << " " << error_msg << std::endl; - return kError; - } + if (doc.HasMember("error")) { + // Error code and message. + error_code = doc["error"]["code"].GetInt(); + data = doc["error"]["message"].GetString(); + // std::cout << "Error: " << error_id << " " << error_msg << std::endl; + return kError; + } - if (doc.HasMember("result")) - { - rapidjson::StringBuffer buffer; - buffer.Clear(); - rapidjson::Writer writer(buffer); - doc["result"].Accept(writer); - data = buffer.GetString(); - return kResult; - } - return kInvalid; - + if (doc.HasMember("result")) { + rapidjson::StringBuffer buffer; + buffer.Clear(); + rapidjson::Writer writer(buffer); + doc["result"].Accept(writer); + data = buffer.GetString(); + return kResult; } -} \ No newline at end of file + return kInvalid; +} +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/protos/utils.hh b/sdk/src/protos/utils.hh index d3c7d82..3139380 100644 --- a/sdk/src/protos/utils.hh +++ b/sdk/src/protos/utils.hh @@ -1,47 +1,51 @@ #include "jsonbase.hh" #include "rapidjson/rapidjson.h" -#include "rapidjson/document.h" // rapidjson's DOM-style API -#include "rapidjson/stringbuffer.h" // wrapper of C stream for prettywriter as output -#include "rapidjson/prettywriter.h" // for stringify JSON +#include "rapidjson/document.h" // rapidjson's DOM-style API +#include "rapidjson/stringbuffer.h" // wrapper of C stream for prettywriter as output +#include "rapidjson/prettywriter.h" // for stringify JSON #pragma once -namespace lebai -{ - /** - * @brief Generate a json rpc request string from id, method and a json data as params. - * - * @param id The id of the request. - * @param method The method name. - * @param data The json data strucutre for params. - * @return std::string A json rpc request string. - */ - std::string ToJSONRpcReqString(int id, const std::string & method, const JSONBase & data); - /** - * @brief Generate a json rpc request string from id, method and a params string. - * - * @param id The id of the request. - * @param method The method name. - * @param data The params strucutre. - * @return std::string A json rpc request string. - */ - std::string ToJSONRpcReqString(int id, const std::string & method, const std::string & data); - // int FromJSONRpcRespString(const std::string &s, JSONBase & data); - enum JSONRpcRespParseResult - { - kResult = 0, - kError = -1, - kInvalid = -2, - }; - /** - * @brief Get the result from a json rpc response string. - * - * @param s The json rpc response string. - * @param id The id of the response. - * @param error_code The error code of the response. - * @param data The response string data. - * @return int return code. if 0, success. if not 0, it's not a valid response. - */ +namespace lebai { +/** + * @brief Generate a json rpc request string from id, method and a json data as + * params. + * + * @param id The id of the request. + * @param method The method name. + * @param data The json data strucutre for params. + * @return std::string A json rpc request string. + */ +std::string ToJSONRpcReqString(int id, const std::string &method, + const JSONBase &data); +/** + * @brief Generate a json rpc request string from id, method and a params + * string. + * + * @param id The id of the request. + * @param method The method name. + * @param data The params strucutre. + * @return std::string A json rpc request string. + */ +std::string ToJSONRpcReqString(int id, const std::string &method, + const std::string &data); +// int FromJSONRpcRespString(const std::string &s, JSONBase & data); +enum JSONRpcRespParseResult { + kResult = 0, + kError = -1, + kInvalid = -2, +}; +/** + * @brief Get the result from a json rpc response string. + * + * @param s The json rpc response string. + * @param id The id of the response. + * @param error_code The error code of the response. + * @param data The response string data. + * @return int return code. if 0, success. if not 0, it's not a valid response. + */ - JSONRpcRespParseResult ExtractJSONRpcRespString(const std::string &s, int & id, int & error_code, std::string & data); -} \ No newline at end of file +JSONRpcRespParseResult ExtractJSONRpcRespString(const std::string &s, int &id, + int &error_code, + std::string &data); +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/robot.cc b/sdk/src/robot.cc index 0d00e8d..3c0c87c 100644 --- a/sdk/src/robot.cc +++ b/sdk/src/robot.cc @@ -1,18 +1,18 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #include #include @@ -21,19 +21,11 @@ #include "protos/serial.hh" #include - - namespace lebai { -namespace l_master -{ +namespace l_master { - std::string version() - { - return LEBAI_SDK_VERSION_STR ; - } - - +std::string version() { return LEBAI_SDK_VERSION_STR; } Robot::Robot(std::string ip, bool simulator) // :ip_(ip) @@ -42,406 +34,340 @@ Robot::Robot(std::string ip, bool simulator) } Robot::~Robot() {} -std::tuple Robot::call(const std::string & method, const std::string & params) -{ +std::tuple Robot::call(const std::string &method, + const std::string ¶ms) { return impl_->call(method, params); } -bool Robot::is_network_connected() -{ - return impl_->isNetworkConnected(); -} +bool Robot::is_network_connected() { return impl_->isNetworkConnected(); } -void Robot::start_sys() -{ - impl_->startSys(); -} +void Robot::start_sys() { impl_->startSys(); } -void Robot::stop_sys() -{ - impl_->stopSys(); -} +void Robot::stop_sys() { impl_->stopSys(); } -void Robot::powerdown() -{ - impl_->powerdown(); -} +void Robot::powerdown() { impl_->powerdown(); } -void Robot::stop() -{ - impl_->stop(); -} +void Robot::stop() { impl_->stop(); } -void Robot::estop() -{ - impl_->estop(); -} +void Robot::estop() { impl_->estop(); } -void Robot::teach_mode() -{ - impl_->teachMode(); -} +void Robot::teach_mode() { impl_->teachMode(); } -void Robot::end_teach_mode() -{ - impl_->endTeachMode(); -} +void Robot::end_teach_mode() { impl_->endTeachMode(); } -void Robot::pause() -{ - impl_->pause(); -} +void Robot::pause() { impl_->pause(); } -void Robot::resume() -{ - impl_->resume(); -} +void Robot::resume() { impl_->resume(); } -void Robot::reboot() -{ - impl_->reboot(); -} +void Robot::reboot() { impl_->reboot(); } -int Robot::movej(const std::vector & joint_positions, double a, double v, double t, double r) -{ +int Robot::movej(const std::vector &joint_positions, double a, double v, + double t, double r) { motion::MoveRequest move_req; move_req.mutable_param()->set_acc(a); move_req.mutable_param()->set_velocity(v); move_req.mutable_param()->set_time(t); move_req.mutable_param()->set_radius(r); motion::MotionIndex resp; - for(auto && p :joint_positions) - { + for (auto &&p : joint_positions) { move_req.mutable_pose()->mutable_joint()->mutable_joint()->push_back(p); } resp = impl_->moveJoint(move_req); return resp.id(); } -int Robot::movej(const CartesianPose & cart_pose, double a, double v, double t, double r) -{ +int Robot::movej(const CartesianPose &cart_pose, double a, double v, double t, + double r) { motion::MoveRequest move_req; move_req.mutable_param()->set_acc(a); move_req.mutable_param()->set_velocity(v); move_req.mutable_param()->set_time(t); move_req.mutable_param()->set_radius(r); - if(cart_pose.find("x") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_x(cart_pose.at("x")); - } - else - { + if (cart_pose.find("x") != cart_pose.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_x( + cart_pose.at("x")); + } else { return -1; } - if(cart_pose.find("y") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_y(cart_pose.at("y")); - } - else - { + if (cart_pose.find("y") != cart_pose.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_y( + cart_pose.at("y")); + } else { return -1; } - if(cart_pose.find("z") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_z(cart_pose.at("z")); - } - else - { + if (cart_pose.find("z") != cart_pose.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_z( + cart_pose.at("z")); + } else { return -1; } - if(cart_pose.find("rx") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(cart_pose.at("rx")); - } - else - { + if (cart_pose.find("rx") != cart_pose.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(cart_pose.at("rx")); + } else { return -1; } - if(cart_pose.find("ry") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(cart_pose.at("ry")); - } - else - { + if (cart_pose.find("ry") != cart_pose.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(cart_pose.at("ry")); + } else { return -1; } - if(cart_pose.find("rz") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(cart_pose.at("rz")); - } - else - { + if (cart_pose.find("rz") != cart_pose.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(cart_pose.at("rz")); + } else { return -1; } motion::MotionIndex resp = impl_->moveJoint(move_req); return resp.id(); } - -int Robot::movel(const std::vector & joint_positions, double a, double v, double t, double r) -{ +int Robot::movel(const std::vector &joint_positions, double a, double v, + double t, double r) { motion::MoveRequest move_req; move_req.mutable_param()->set_acc(a); move_req.mutable_param()->set_velocity(v); move_req.mutable_param()->set_time(t); move_req.mutable_param()->set_radius(r); - for(auto && p :joint_positions) - { + for (auto &&p : joint_positions) { move_req.mutable_pose()->mutable_joint()->mutable_joint()->push_back(p); } motion::MotionIndex resp = impl_->moveLinear(move_req); return resp.id(); } -int Robot::movel(const CartesianPose & cart_pose, double a, double v, double t, double r) -{ +int Robot::movel(const CartesianPose &cart_pose, double a, double v, double t, + double r) { motion::MoveRequest move_req; move_req.mutable_param()->set_acc(a); move_req.mutable_param()->set_velocity(v); move_req.mutable_param()->set_time(t); move_req.mutable_param()->set_radius(r); - if(cart_pose.find("x") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_x(cart_pose.at("x")); - } - else - { + if (cart_pose.find("x") != cart_pose.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_x( + cart_pose.at("x")); + } else { return -1; } - if(cart_pose.find("y") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_y(cart_pose.at("y")); - } - else - { + if (cart_pose.find("y") != cart_pose.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_y( + cart_pose.at("y")); + } else { return -1; } - if(cart_pose.find("z") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_z(cart_pose.at("z")); - } - else - { + if (cart_pose.find("z") != cart_pose.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_z( + cart_pose.at("z")); + } else { return -1; } - if(cart_pose.find("rx") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(cart_pose.at("rx")); - } - else - { + if (cart_pose.find("rx") != cart_pose.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(cart_pose.at("rx")); + } else { return -1; } - if(cart_pose.find("ry") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(cart_pose.at("ry")); - } - else - { + if (cart_pose.find("ry") != cart_pose.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(cart_pose.at("ry")); + } else { return -1; } - if(cart_pose.find("rz") != cart_pose.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(cart_pose.at("rz")); - } - else - { + if (cart_pose.find("rz") != cart_pose.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(cart_pose.at("rz")); + } else { return -1; } motion::MotionIndex resp = impl_->moveLinear(move_req); return resp.id(); } -int Robot::movec(const std::vector & joint_via, const std::vector & joint, double rad, double a, double v, double t, double r) -{ +int Robot::movec(const std::vector &joint_via, + const std::vector &joint, double rad, double a, + double v, double t, double r) { motion::MovecRequest move_req; move_req.mutable_param()->set_acc(a); move_req.mutable_param()->set_velocity(v); move_req.mutable_param()->set_time(t); move_req.mutable_param()->set_radius(r); move_req.set_rad(rad); - for(auto && p :joint_via) - { + for (auto &&p : joint_via) { move_req.mutable_pose_via()->mutable_joint()->mutable_joint()->push_back(p); } - for(auto && p :joint) - { + for (auto &&p : joint) { move_req.mutable_pose()->mutable_joint()->mutable_joint()->push_back(p); } motion::MotionIndex resp = impl_->moveCircular(move_req); return resp.id(); } -int Robot::movec(const CartesianPose & cart_via, const CartesianPose & cart, double rad, double a, double v, double t, double r) -{ +int Robot::movec(const CartesianPose &cart_via, const CartesianPose &cart, + double rad, double a, double v, double t, double r) { motion::MovecRequest move_req; move_req.mutable_param()->set_acc(a); move_req.mutable_param()->set_velocity(v); move_req.mutable_param()->set_time(t); move_req.mutable_param()->set_radius(r); move_req.set_rad(rad); - if(cart_via.find("x") != cart_via.end()) - { - move_req.mutable_pose_via()->mutable_cart()->mutable_position()->set_x(cart_via.at("x")); - } - else - { + if (cart_via.find("x") != cart_via.end()) { + move_req.mutable_pose_via()->mutable_cart()->mutable_position()->set_x( + cart_via.at("x")); + } else { return -1; } - if(cart_via.find("y") != cart_via.end()) - { - move_req.mutable_pose_via()->mutable_cart()->mutable_position()->set_y(cart_via.at("y")); - } - else - { + if (cart_via.find("y") != cart_via.end()) { + move_req.mutable_pose_via()->mutable_cart()->mutable_position()->set_y( + cart_via.at("y")); + } else { return -1; } - if(cart_via.find("z") != cart_via.end()) - { - move_req.mutable_pose_via()->mutable_cart()->mutable_position()->set_z(cart_via.at("z")); - } - else - { + if (cart_via.find("z") != cart_via.end()) { + move_req.mutable_pose_via()->mutable_cart()->mutable_position()->set_z( + cart_via.at("z")); + } else { return -1; } - if(cart_via.find("rx") != cart_via.end()) - { - move_req.mutable_pose_via()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(cart_via.at("rx")); - } - else - { + if (cart_via.find("rx") != cart_via.end()) { + move_req.mutable_pose_via() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(cart_via.at("rx")); + } else { return -1; } - if(cart_via.find("ry") != cart_via.end()) - { - move_req.mutable_pose_via()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(cart_via.at("ry")); - } - else - { + if (cart_via.find("ry") != cart_via.end()) { + move_req.mutable_pose_via() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(cart_via.at("ry")); + } else { return -1; } - if(cart_via.find("rz") != cart_via.end()) - { - move_req.mutable_pose_via()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(cart_via.at("rz")); - } - else - { + if (cart_via.find("rz") != cart_via.end()) { + move_req.mutable_pose_via() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(cart_via.at("rz")); + } else { return -1; } - if(cart.find("x") != cart.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_x(cart.at("x")); - } - else - { + if (cart.find("x") != cart.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_x( + cart.at("x")); + } else { return -1; } - if(cart.find("y") != cart.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_y(cart.at("y")); - } - else - { + if (cart.find("y") != cart.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_y( + cart.at("y")); + } else { return -1; } - if(cart.find("z") != cart.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_position()->set_z(cart.at("z")); - } - else - { + if (cart.find("z") != cart.end()) { + move_req.mutable_pose()->mutable_cart()->mutable_position()->set_z( + cart.at("z")); + } else { return -1; } - if(cart.find("rx") != cart.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(cart.at("rx")); - } - else - { + if (cart.find("rx") != cart.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(cart.at("rx")); + } else { return -1; } - if(cart.find("ry") != cart.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(cart.at("ry")); - } - else - { + if (cart.find("ry") != cart.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(cart.at("ry")); + } else { return -1; } - if(cart.find("rz") != cart.end()) - { - move_req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(cart.at("rz")); - } - else - { + if (cart.find("rz") != cart.end()) { + move_req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(cart.at("rz")); + } else { return -1; } motion::MotionIndex resp = impl_->moveCircular(move_req); return resp.id(); } -int Robot::speedj(double a, const std::vector & v, double t) -{ +int Robot::speedj(double a, const std::vector &v, double t) { motion::SpeedJRequest req; req.mutable_param()->set_acc(a); req.mutable_param()->set_time(a); - for(auto && p :v) - { + for (auto &&p : v) { req.mutable_speed()->mutable_joint()->push_back(p); } lebai::motion::MotionIndex resp = impl_->speedJoint(req); return resp.id(); } -int Robot::speedl(double a, const CartesianPose & v, double t, const CartesianPose & reference) -{ +int Robot::speedl(double a, const CartesianPose &v, double t, + const CartesianPose &reference) { motion::SpeedLRequest req; req.mutable_param()->set_acc(a); req.mutable_param()->set_time(a); - if(v.find("x") != v.end()) - { + if (v.find("x") != v.end()) { req.mutable_speed()->mutable_position()->set_x(v.at("x")); - } - else - { + } else { return -1; } - if(v.find("y") != v.end()) - { + if (v.find("y") != v.end()) { req.mutable_speed()->mutable_position()->set_y(v.at("y")); - } - else - { + } else { return -1; } - if(v.find("z") != v.end()) - { + if (v.find("z") != v.end()) { req.mutable_speed()->mutable_position()->set_z(v.at("z")); - } - else - { + } else { return -1; } - if(v.find("rx") != v.end()) - { - req.mutable_speed()->mutable_rotation()->mutable_euler_zyx()->set_x(v.at("rx")); - } - else - { + if (v.find("rx") != v.end()) { + req.mutable_speed()->mutable_rotation()->mutable_euler_zyx()->set_x( + v.at("rx")); + } else { return -1; } - if(v.find("ry") != v.end()) - { - req.mutable_speed()->mutable_rotation()->mutable_euler_zyx()->set_y(v.at("ry")); - } - else - { + if (v.find("ry") != v.end()) { + req.mutable_speed()->mutable_rotation()->mutable_euler_zyx()->set_y( + v.at("ry")); + } else { return -1; } - if(v.find("rz") != v.end()) - { - req.mutable_speed()->mutable_rotation()->mutable_euler_zyx()->set_z(v.at("rz")); - } - else - { + if (v.find("rz") != v.end()) { + req.mutable_speed()->mutable_rotation()->mutable_euler_zyx()->set_z( + v.at("rz")); + } else { return -1; } // if(reference == BASE) { @@ -449,7 +375,7 @@ int Robot::speedl(double a, const CartesianPose & v, double t, const CartesianPo // req.mutable_frame()->set_rotation_kind(posture::CartesianFrame::Kind::BASE); // } else if(reference == FLANGE) { // req.mutable_frame()->set_position_kind(posture::CartesianFrame::Kind::FLANGE); - // req.mutable_frame()->set_rotation_kind(posture::CartesianFrame::Kind::FLANGE); + // req.mutable_frame()->set_rotation_kind(posture::CartesianFrame::Kind::FLANGE); // } else if(reference == TCP) { // auto tcp = get_target_tcp_pose(); // req.mutable_frame()->mutable_position()->set_x(tcp["x"]); @@ -466,80 +392,62 @@ int Robot::speedl(double a, const CartesianPose & v, double t, const CartesianPo req.mutable_frame()->set_position_kind(posture::CartesianFrame::Kind::CUSTOM); req.mutable_frame()->set_rotation_kind(posture::CartesianFrame::Kind::CUSTOM); - if(reference.find("x") != reference.end()) - { + if (reference.find("x") != reference.end()) { req.mutable_frame()->mutable_position()->set_x(reference.at("x")); - } - else - { + } else { return -1; } - if(reference.find("y") != reference.end()) - { + if (reference.find("y") != reference.end()) { req.mutable_frame()->mutable_position()->set_y(reference.at("y")); - } - else - { + } else { return -1; } - if(reference.find("z") != reference.end()) - { + if (reference.find("z") != reference.end()) { req.mutable_frame()->mutable_position()->set_z(reference.at("z")); - } - else - { + } else { return -1; } - if(reference.find("rx") != reference.end()) - { - req.mutable_frame()->mutable_rotation()->mutable_euler_zyx()->set_x(reference.at("rx")); - } - else - { + if (reference.find("rx") != reference.end()) { + req.mutable_frame()->mutable_rotation()->mutable_euler_zyx()->set_x( + reference.at("rx")); + } else { return -1; } - if(reference.find("ry") != reference.end()) - { - req.mutable_frame()->mutable_rotation()->mutable_euler_zyx()->set_y(reference.at("ry")); - } - else - { + if (reference.find("ry") != reference.end()) { + req.mutable_frame()->mutable_rotation()->mutable_euler_zyx()->set_y( + reference.at("ry")); + } else { return -1; } - if(reference.find("rz") != reference.end()) - { - req.mutable_frame()->mutable_rotation()->mutable_euler_zyx()->set_z(reference.at("rz")); - } - else - { + if (reference.find("rz") != reference.end()) { + req.mutable_frame()->mutable_rotation()->mutable_euler_zyx()->set_z( + reference.at("rz")); + } else { return -1; } lebai::motion::MotionIndex resp = impl_->speedLinear(req); return resp.id(); } - -int Robot::towardj(const std::vector & joint_positions, double a, double v, double t, double r) -{ +int Robot::towardj(const std::vector &joint_positions, double a, + double v, double t, double r) { motion::MoveRequest move_req; move_req.mutable_param()->set_acc(a); move_req.mutable_param()->set_velocity(v); move_req.mutable_param()->set_time(t); move_req.mutable_param()->set_radius(r); - for(auto && p :joint_positions) - { + for (auto &&p : joint_positions) { move_req.mutable_pose()->mutable_joint()->mutable_joint()->push_back(p); } motion::MotionIndex resp = impl_->towardJoint(move_req); return resp.id(); } -void Robot::move_pvat(std::vector p, std::vector v, std::vector a, double t) -{ +void Robot::move_pvat(std::vector p, std::vector v, + std::vector a, double t) { motion::MovePvatRequest req; std::vector joints; - for(int i = 0;i < p.size();i++) - { + for (int i = 0; i < p.size(); i++) { motion::JointMove joint; joint.set_pose(p[i]); joint.set_velocity(v[i]); @@ -551,108 +459,84 @@ void Robot::move_pvat(std::vector p, std::vector v, std::vector< impl_->movePvat(req); } -void Robot::wait_move(unsigned int id) -{ +void Robot::wait_move(unsigned int id) { motion::MotionIndex req; req.set_id(id); impl_->waitMove(req); } -void Robot::wait_move() -{ +void Robot::wait_move() { motion::MotionIndex req; req.set_id(0); impl_->waitMove(req); } -unsigned int Robot::get_running_motion() -{ +unsigned int Robot::get_running_motion() { motion::MotionIndex resp = impl_->getRunningMotion(); return resp.id(); } -std::string Robot::get_motion_state(unsigned int id) -{ +std::string Robot::get_motion_state(unsigned int id) { motion::MotionIndex req; req.set_id(id); motion::GetMotionStateResponse resp = impl_->getMotionState(req); - switch(resp.state()) - { - case motion::WAIT:return (std::string)"WAIT"; - case motion::RUNNING:return (std::string)"RUNNING"; - case motion::FINISHED:return (std::string)"FINISHED"; - default:return (std::string)"WAIT"; + switch (resp.state()) { + case motion::WAIT: + return (std::string) "WAIT"; + case motion::RUNNING: + return (std::string) "RUNNING"; + case motion::FINISHED: + return (std::string) "FINISHED"; + default: + return (std::string) "WAIT"; } } -void Robot::stop_move() -{ - impl_->stopMove(); -} +void Robot::stop_move() { impl_->stopMove(); } -int Robot::get_robot_mode() -{ - return impl_->getRobotState(); -} +int Robot::get_robot_mode() { return impl_->getRobotState(); } -int Robot::get_estop_reason() -{ - return impl_->getEstopReason(); -} - -bool Robot::is_disconnected() -{ - return impl_->getRobotState() == 0; -} +int Robot::get_estop_reason() { return impl_->getEstopReason(); } -bool Robot::is_down() -{ - return impl_->getRobotState() < 4; -} +bool Robot::is_disconnected() { return impl_->getRobotState() == 0; } -std::vector Robot::get_actual_joint_positions() -{ +bool Robot::is_down() { return impl_->getRobotState() < 4; } + +std::vector Robot::get_actual_joint_positions() { std::map ret; return *impl_->getKinData().mutable_actual_joint_pose(); } -std::vector Robot::get_target_joint_positions() -{ +std::vector Robot::get_target_joint_positions() { std::map ret; return *impl_->getKinData().mutable_target_joint_pose(); } -std::vector Robot::get_actual_joint_speed() -{ +std::vector Robot::get_actual_joint_speed() { return *impl_->getKinData().mutable_actual_joint_speed(); } -std::vector Robot::get_target_joint_speed() -{ - return *impl_->getKinData().mutable_target_joint_speed(); +std::vector Robot::get_target_joint_speed() { + return *impl_->getKinData().mutable_target_joint_speed(); } -CartesianPose Robot::get_actual_tcp_pose() -{ +CartesianPose Robot::get_actual_tcp_pose() { auto pose = impl_->getKinData().actual_tcp_pose(); CartesianPose cart_pose; cart_pose["x"] = pose.position().x(); cart_pose["y"] = pose.position().y(); cart_pose["z"] = pose.position().z(); - if(pose.rotation().euler_zyx()) - { + if (pose.rotation().euler_zyx()) { cart_pose["rz"] = pose.rotation().euler_zyx()->z(); cart_pose["ry"] = pose.rotation().euler_zyx()->y(); cart_pose["rx"] = pose.rotation().euler_zyx()->x(); } return cart_pose; } -CartesianPose Robot::get_target_tcp_pose() -{ +CartesianPose Robot::get_target_tcp_pose() { auto pose = impl_->getKinData().target_tcp_pose(); CartesianPose cart_pose; cart_pose["x"] = pose.position().x(); cart_pose["y"] = pose.position().y(); cart_pose["z"] = pose.position().z(); - if(pose.rotation().euler_zyx()) - { + if (pose.rotation().euler_zyx()) { cart_pose["rz"] = pose.rotation().euler_zyx()->z(); cart_pose["ry"] = pose.rotation().euler_zyx()->y(); cart_pose["rx"] = pose.rotation().euler_zyx()->x(); @@ -660,63 +544,46 @@ CartesianPose Robot::get_target_tcp_pose() return cart_pose; } -double Robot::get_joint_temp(unsigned int joint_index) -{ - auto data = impl_->getPhyData(); - joint_index -= 1; - if(data.joint_temp().size() > joint_index) - { +double Robot::get_joint_temp(unsigned int joint_index) { + auto data = impl_->getPhyData(); + joint_index -= 1; + if (data.joint_temp().size() > joint_index) { return data.joint_temp()[joint_index]; } return 0.0; } -std::vector Robot::get_actual_joint_torques() -{ - return impl_->getKinData().actual_joint_torque(); +std::vector Robot::get_actual_joint_torques() { + return impl_->getKinData().actual_joint_torque(); } -std::vector Robot::get_target_joint_torques() -{ - return impl_->getKinData().target_joint_torque(); +std::vector Robot::get_target_joint_torques() { + return impl_->getKinData().target_joint_torque(); } - -void Robot::set_do(std::string device, unsigned int pin, unsigned int value) -{ +void Robot::set_do(std::string device, unsigned int pin, unsigned int value) { io::SetDoPinRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); req.set_value(value); impl_->setDO(req); } -unsigned int Robot::get_do(std::string device, unsigned int pin) -{ +unsigned int Robot::get_do(std::string device, unsigned int pin) { io::GetDioPinRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); @@ -724,21 +591,16 @@ unsigned int Robot::get_do(std::string device, unsigned int pin) return resp.value(); } -std::vector Robot::get_dos(std::string device, unsigned int pin, unsigned int num) -{ +std::vector Robot::get_dos(std::string device, unsigned int pin, + unsigned int num) { io::GetDioPinsRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); @@ -747,20 +609,14 @@ std::vector Robot::get_dos(std::string device, unsigned int pin, u return resp.values(); } -unsigned int Robot::get_di(std::string device, unsigned int pin) -{ +unsigned int Robot::get_di(std::string device, unsigned int pin) { io::GetDioPinRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); @@ -768,20 +624,15 @@ unsigned int Robot::get_di(std::string device, unsigned int pin) return resp.value(); } -std::vector Robot::get_dis(std::string device, unsigned int pin, unsigned int num) -{ +std::vector Robot::get_dis(std::string device, unsigned int pin, + unsigned int num) { io::GetDioPinsRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); req.set_count(num); @@ -789,60 +640,43 @@ std::vector Robot::get_dis(std::string device, unsigned int pin, u return resp.values(); } -void Robot::set_ao(std::string device, unsigned int pin, double value) -{ +void Robot::set_ao(std::string device, unsigned int pin, double value) { io::SetAoPinRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); req.set_value(value); impl_->setAO(req); } -double Robot::get_ao(std::string device, unsigned int pin) -{ +double Robot::get_ao(std::string device, unsigned int pin) { io::GetAioPinRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); io::GetAioPinResponse resp = impl_->getAO(req); return resp.value(); } -std::vector Robot::get_aos(std::string device, unsigned int pin, unsigned int num) -{ +std::vector Robot::get_aos(std::string device, unsigned int pin, + unsigned int num) { io::GetAioPinsRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); req.set_count(num); @@ -850,79 +684,57 @@ std::vector Robot::get_aos(std::string device, unsigned int pin, unsigne return resp.values(); } -double Robot::get_ai(std::string device, unsigned int pin) -{ +double Robot::get_ai(std::string device, unsigned int pin) { io::GetAioPinRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); io::GetAioPinResponse resp = impl_->getAI(req); return resp.value(); } -std::vector Robot::get_ais(std::string device, unsigned int pin, unsigned int num) -{ +std::vector Robot::get_ais(std::string device, unsigned int pin, + unsigned int num) { io::GetAioPinsRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); req.set_count(num); io::GetAioPinsResponse resp = impl_->getAIS(req); return resp.values(); } -void Robot::set_dio_mode(std::string device,unsigned int pin, bool value) -{ +void Robot::set_dio_mode(std::string device, unsigned int pin, bool value) { io::SetDioModeRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); req.set_value(value); impl_->setDioMode(req); } -std::vector Robot::get_dios_mode(std::string device,unsigned int pin, unsigned int count) -{ +std::vector Robot::get_dios_mode(std::string device, unsigned int pin, + unsigned int count) { io::GetDiosModeRequest req; - if(device == "ROBOT") - { + if (device == "ROBOT") { req.set_device(io::IoDevice::ROBOT); - } - else if(device == "FLANGE") - { + } else if (device == "FLANGE") { req.set_device(io::IoDevice::FLANGE); - } - else if(device == "EXTRA") - { - req.set_device(io::IoDevice::EXTRA); + } else if (device == "EXTRA") { + req.set_device(io::IoDevice::EXTRA); } req.set_pin(pin); req.set_count(count); @@ -930,22 +742,19 @@ std::vector Robot::get_dios_mode(std::string device,unsigned int pin, unsi return resp.values(); } -void Robot::set_claw(double force, double amplitude) -{ +void Robot::set_claw(double force, double amplitude) { claw::SetClawRequest req; req.set_force(force); req.set_amplitude(amplitude); - impl_->setClaw(req); + impl_->setClaw(req); } -std::tuple Robot::get_claw() -{ +std::tuple Robot::get_claw() { auto resp = impl_->getClaw(); return std::make_tuple(resp.force(), resp.amplitude(), resp.hold_on()); } -ClawData Robot::get_claw_data() -{ +ClawData Robot::get_claw_data() { auto resp = impl_->getClaw(); ClawData claw_data; claw_data.force = resp.force(); @@ -954,126 +763,223 @@ ClawData Robot::get_claw_data() return claw_data; } -void Robot::set_led(unsigned int mode,unsigned int speed,const std::vector & color) -{ +void Robot::set_led(unsigned int mode, unsigned int speed, + const std::vector &color) { led::LedData req; - switch(mode) - { - case 0:req.set_mode(led::LedMode::HOLD_LED);break; - case 1:req.set_mode(led::LedMode::CLOSE_LED);break; - case 2:req.set_mode(led::LedMode::OPEN_LED);break; - case 3:req.set_mode(led::LedMode::BREATH);break; - case 4:req.set_mode(led::LedMode::FOUR);break; - case 5:req.set_mode(led::LedMode::WATER);break; - case 6:req.set_mode(led::LedMode::BLINK);break; - default:return; - } - switch(speed) - { - case 0:req.set_speed(led::LedSpeed::HOLD_LED_SPEED);break; - case 1:req.set_speed(led::LedSpeed::FAST);break; - case 2:req.set_speed(led::LedSpeed::NORMAL);break; - case 3:req.set_speed(led::LedSpeed::SLOW);break; - default:return; + switch (mode) { + case 0: + req.set_mode(led::LedMode::HOLD_LED); + break; + case 1: + req.set_mode(led::LedMode::CLOSE_LED); + break; + case 2: + req.set_mode(led::LedMode::OPEN_LED); + break; + case 3: + req.set_mode(led::LedMode::BREATH); + break; + case 4: + req.set_mode(led::LedMode::FOUR); + break; + case 5: + req.set_mode(led::LedMode::WATER); + break; + case 6: + req.set_mode(led::LedMode::BLINK); + break; + default: + return; + } + switch (speed) { + case 0: + req.set_speed(led::LedSpeed::HOLD_LED_SPEED); + break; + case 1: + req.set_speed(led::LedSpeed::FAST); + break; + case 2: + req.set_speed(led::LedSpeed::NORMAL); + break; + case 3: + req.set_speed(led::LedSpeed::SLOW); + break; + default: + return; } std::vector _color; - for(auto _c:color){ - switch(_c) - { - case 0:_color.push_back(led::LedColor::RED);break; - case 1:_color.push_back(led::LedColor::GREEN);break; - case 2:_color.push_back(led::LedColor::BLUE);break; - case 3:_color.push_back(led::LedColor::PINK);break; - case 4:_color.push_back(led::LedColor::YELLOW);break; - case 5:_color.push_back(led::LedColor::CYAN);break; - case 6:_color.push_back(led::LedColor::GRAY);break; - case 7:_color.push_back(led::LedColor::BROWN);break; - case 8:_color.push_back(led::LedColor::ORANGE);break; - case 9:_color.push_back(led::LedColor::GOLD);break; - case 10:_color.push_back(led::LedColor::INDIGO);break; - case 11:_color.push_back(led::LedColor::LIGHT_SKY_BLUE);break; - case 12:_color.push_back(led::LedColor::DARK_VIOLET);break; - case 13:_color.push_back(led::LedColor::CHOCOLATE);break; - case 14:_color.push_back(led::LedColor::LIGHT_RED);break; - case 15:_color.push_back(led::LedColor::WHITE);break; - default:return; + for (auto _c : color) { + switch (_c) { + case 0: + _color.push_back(led::LedColor::RED); + break; + case 1: + _color.push_back(led::LedColor::GREEN); + break; + case 2: + _color.push_back(led::LedColor::BLUE); + break; + case 3: + _color.push_back(led::LedColor::PINK); + break; + case 4: + _color.push_back(led::LedColor::YELLOW); + break; + case 5: + _color.push_back(led::LedColor::CYAN); + break; + case 6: + _color.push_back(led::LedColor::GRAY); + break; + case 7: + _color.push_back(led::LedColor::BROWN); + break; + case 8: + _color.push_back(led::LedColor::ORANGE); + break; + case 9: + _color.push_back(led::LedColor::GOLD); + break; + case 10: + _color.push_back(led::LedColor::INDIGO); + break; + case 11: + _color.push_back(led::LedColor::LIGHT_SKY_BLUE); + break; + case 12: + _color.push_back(led::LedColor::DARK_VIOLET); + break; + case 13: + _color.push_back(led::LedColor::CHOCOLATE); + break; + case 14: + _color.push_back(led::LedColor::LIGHT_RED); + break; + case 15: + _color.push_back(led::LedColor::WHITE); + break; + default: + return; } } req.set_colors(_color); impl_->setLed(req); } -void Robot::set_voice(unsigned int voice,unsigned int volume) -{ +void Robot::set_voice(unsigned int voice, unsigned int volume) { led::VoiceData req; - switch(voice) - { - case 0:req.set_voice(led::VoiceKind::OFF);break; - case 1:req.set_voice(led::VoiceKind::BOOTING);break; - case 2:req.set_voice(led::VoiceKind::STOPING);break; - case 3:req.set_voice(led::VoiceKind::COLLISION_DETECTED);break; - case 4:req.set_voice(led::VoiceKind::UPGRADE);break; - case 5:req.set_voice(led::VoiceKind::TEACH_MODE_ON);break; - case 6:req.set_voice(led::VoiceKind::TEACH_MODE_OFF);break; - case 7:req.set_voice(led::VoiceKind::FINE_TUNNING_ON);break; - case 8:req.set_voice(led::VoiceKind::FINE_TUNNING_OFF);break; - case 9:req.set_voice(led::VoiceKind::FINE_TUNNING_CHANGE);break; - case 10:req.set_voice(led::VoiceKind::BORING);break; - case 11:req.set_voice(led::VoiceKind::CUSTOM1);break; - case 12:req.set_voice(led::VoiceKind::CUSTOM2);break; - case 13:req.set_voice(led::VoiceKind::CUSTOM3);break; - case 14:req.set_voice(led::VoiceKind::CUSTOM4);break; - case 15:req.set_voice(led::VoiceKind::CUSTOM5);break; - default:return; - } - switch(volume) - { - case 0:req.set_volume(led::Volume::MUTE);break; - case 1:req.set_volume(led::Volume::LOW);break; - case 2:req.set_volume(led::Volume::MID);break; - case 3:req.set_volume(led::Volume::HIGH);break; - default:return; + switch (voice) { + case 0: + req.set_voice(led::VoiceKind::OFF); + break; + case 1: + req.set_voice(led::VoiceKind::BOOTING); + break; + case 2: + req.set_voice(led::VoiceKind::STOPING); + break; + case 3: + req.set_voice(led::VoiceKind::COLLISION_DETECTED); + break; + case 4: + req.set_voice(led::VoiceKind::UPGRADE); + break; + case 5: + req.set_voice(led::VoiceKind::TEACH_MODE_ON); + break; + case 6: + req.set_voice(led::VoiceKind::TEACH_MODE_OFF); + break; + case 7: + req.set_voice(led::VoiceKind::FINE_TUNNING_ON); + break; + case 8: + req.set_voice(led::VoiceKind::FINE_TUNNING_OFF); + break; + case 9: + req.set_voice(led::VoiceKind::FINE_TUNNING_CHANGE); + break; + case 10: + req.set_voice(led::VoiceKind::BORING); + break; + case 11: + req.set_voice(led::VoiceKind::CUSTOM1); + break; + case 12: + req.set_voice(led::VoiceKind::CUSTOM2); + break; + case 13: + req.set_voice(led::VoiceKind::CUSTOM3); + break; + case 14: + req.set_voice(led::VoiceKind::CUSTOM4); + break; + case 15: + req.set_voice(led::VoiceKind::CUSTOM5); + break; + default: + return; + } + switch (volume) { + case 0: + req.set_volume(led::Volume::MUTE); + break; + case 1: + req.set_volume(led::Volume::LOW); + break; + case 2: + req.set_volume(led::Volume::MID); + break; + case 3: + req.set_volume(led::Volume::HIGH); + break; + default: + return; } impl_->setVoice(req); } -void Robot::set_fan(unsigned int status) -{ +void Robot::set_fan(unsigned int status) { led::FanData req; - switch(status) - { - case 0:req.set_fan(led::FanMode::HOLD_FAN);break; - case 1:req.set_fan(led::FanMode::CLOSE_FAN);break; - case 2:req.set_fan(led::FanMode::OPEN_FAN);break; - default:return; + switch (status) { + case 0: + req.set_fan(led::FanMode::HOLD_FAN); + break; + case 1: + req.set_fan(led::FanMode::CLOSE_FAN); + break; + case 2: + req.set_fan(led::FanMode::OPEN_FAN); + break; + default: + return; } impl_->setFan(req); } -void Robot::set_signal(unsigned int index,int value) -{ +void Robot::set_signal(unsigned int index, int value) { signal::SetSignalRequest req; req.set_key(index); req.set_value(value); impl_->setSignal(req); } -int Robot::get_signal(unsigned int index) -{ +int Robot::get_signal(unsigned int index) { signal::GetSignalRequest req; req.set_key(index); signal::GetSignalResponse resp = impl_->getSignal(req); return resp.value(); } -void Robot::add_signal(unsigned int index,int value) -{ +void Robot::add_signal(unsigned int index, int value) { signal::SetSignalRequest req; req.set_key(index); req.set_value(value); impl_->addSignal(req); } -unsigned int Robot::start_task(const std::string &name,const std::vector & params,const std::string & dir, bool is_parallel,unsigned int loop_to) -{ +unsigned int Robot::start_task(const std::string &name, + const std::vector ¶ms, + const std::string &dir, bool is_parallel, + unsigned int loop_to) { control::StartTaskRequest req; req.set_name(name); req.set_is_parallel(is_parallel); @@ -1083,8 +989,7 @@ unsigned int Robot::start_task(const std::string &name,const std::vectorscene(req); return resp.id(); } -unsigned int Robot::start_task(const std::string &name) -{ +unsigned int Robot::start_task(const std::string &name) { control::StartTaskRequest req; req.set_name(name); req.set_is_parallel(false); @@ -1092,93 +997,114 @@ unsigned int Robot::start_task(const std::string &name) control::TaskIndex resp = impl_->scene(req); return resp.id(); } -std::vector Robot::load_task_list() -{ +std::vector Robot::load_task_list() { control::TaskIds resp = impl_->loadTaskList(); return resp.ids(); } -void Robot::pause_task(unsigned int id) -{ +void Robot::pause_task(unsigned int id) { control::PauseRequest req; req.set_id(id); req.set_time(0); req.set_wait(false); impl_->pauseTask(req); } -void Robot::pause_task(unsigned int id,unsigned long time,bool wait) -{ +void Robot::pause_task(unsigned int id, unsigned long time, bool wait) { control::PauseRequest req; req.set_id(id); req.set_time(time); req.set_wait(wait); impl_->pauseTask(req); } -void Robot::resume_task(unsigned int id) -{ +void Robot::resume_task(unsigned int id) { control::TaskIndex req; req.set_id(id); impl_->resumeTask(req); } -void Robot::cancel_task(unsigned int id) -{ +void Robot::cancel_task(unsigned int id) { control::TaskIndex req; req.set_id(id); impl_->cancelTask(req); } -unsigned int Robot::exec_hook(unsigned int id) -{ +unsigned int Robot::exec_hook(unsigned int id) { control::Exec req; req.set_id(id); control::HookResponse resp = impl_->execHook(req); - if(!resp.success()) - { + if (!resp.success()) { return 0; } return atoi(resp.error().c_str()); } -std::string Robot::get_task_state(unsigned int id) -{ +std::string Robot::get_task_state(unsigned int id) { control::TaskIndex req; req.set_id(id); control::Task resp = impl_->loadTask(req); - switch(resp.state()) - { - case control::TaskState::NONE:return "NONE";break; - case control::TaskState::WAIT:return "WAIT";break; - case control::TaskState::RUNNING:return "RUNNING";break; - case control::TaskState::PAUSE:return "PAUSE";break; - case control::TaskState::SUCCESS:return "SUCCESS";break; - case control::TaskState::INTERRUPT:return "INTERRUPT";break; - case control::TaskState::FAIL:return "FAIL";break; - case control::TaskState::INTERRUPTING:return "INTERRUPTING";break; - default:return "Undefined State"; - } -} -std::string Robot::get_task_state() -{ + switch (resp.state()) { + case control::TaskState::NONE: + return "NONE"; + break; + case control::TaskState::WAIT: + return "WAIT"; + break; + case control::TaskState::RUNNING: + return "RUNNING"; + break; + case control::TaskState::PAUSE: + return "PAUSE"; + break; + case control::TaskState::SUCCESS: + return "SUCCESS"; + break; + case control::TaskState::INTERRUPT: + return "INTERRUPT"; + break; + case control::TaskState::FAIL: + return "FAIL"; + break; + case control::TaskState::INTERRUPTING: + return "INTERRUPTING"; + break; + default: + return "Undefined State"; + } +} +std::string Robot::get_task_state() { control::Task resp = impl_->loadTask(); - switch(resp.state()) - { - case control::TaskState::NONE:return "NONE";break; - case control::TaskState::WAIT:return "WAIT";break; - case control::TaskState::RUNNING:return "RUNNING";break; - case control::TaskState::PAUSE:return "PAUSE";break; - case control::TaskState::SUCCESS:return "SUCCESS";break; - case control::TaskState::INTERRUPT:return "INTERRUPT";break; - case control::TaskState::FAIL:return "FAIL";break; - case control::TaskState::INTERRUPTING:return "INTERRUPTING";break; - default:return "Undefined State"; - } -} - - -KinematicsForwardResp Robot::kinematics_forward(const std::vector & joint_positions) -{ + switch (resp.state()) { + case control::TaskState::NONE: + return "NONE"; + break; + case control::TaskState::WAIT: + return "WAIT"; + break; + case control::TaskState::RUNNING: + return "RUNNING"; + break; + case control::TaskState::PAUSE: + return "PAUSE"; + break; + case control::TaskState::SUCCESS: + return "SUCCESS"; + break; + case control::TaskState::INTERRUPT: + return "INTERRUPT"; + break; + case control::TaskState::FAIL: + return "FAIL"; + break; + case control::TaskState::INTERRUPTING: + return "INTERRUPTING"; + break; + default: + return "Undefined State"; + } +} + +KinematicsForwardResp Robot::kinematics_forward( + const std::vector &joint_positions) { posture::PoseRequest req; - for( auto && p : joint_positions) - { + for (auto &&p : joint_positions) { req.mutable_pose()->mutable_joint()->mutable_joint()->push_back(p); - } + } auto resp = impl_->getForwardKin(req); KinematicsForwardResp kf_resp; kf_resp.pose["x"] = resp.position().x(); @@ -1191,146 +1117,160 @@ KinematicsForwardResp Robot::kinematics_forward(const std::vector & join return kf_resp; } -KinematicsInverseResp Robot::kinematics_inverse(const CartesianPose & pose, const std::vector & joint_init_positions) -{ +KinematicsInverseResp Robot::kinematics_inverse( + const CartesianPose &pose, + const std::vector &joint_init_positions) { posture::GetInverseKinRequest req; double x = 0.0; - if(pose.find("x") != pose.end()) - { + if (pose.find("x") != pose.end()) { x = pose.at("x"); } double y = 0.0; - if(pose.find("y") != pose.end()) - { + if (pose.find("y") != pose.end()) { y = pose.at("y"); } double z = 0.0; - if(pose.find("z") != pose.end()) - { + if (pose.find("z") != pose.end()) { z = pose.at("z"); } double rx = 0.0; - if(pose.find("rx") != pose.end()) - { + if (pose.find("rx") != pose.end()) { rx = pose.at("rx"); } double ry = 0.0; - if(pose.find("ry") != pose.end()) - { + if (pose.find("ry") != pose.end()) { ry = pose.at("ry"); } double rz = 0.0; - if(pose.find("rz") != pose.end()) - { + if (pose.find("rz") != pose.end()) { rz = pose.at("rz"); } req.mutable_pose()->mutable_cart()->mutable_position()->set_x(x); req.mutable_pose()->mutable_cart()->mutable_position()->set_y(y); req.mutable_pose()->mutable_cart()->mutable_position()->set_z(z); - req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(rz); - req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(ry); - req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(rx); - - for(auto && p: joint_init_positions) - { + req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(rz); + req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(ry); + req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(rx); + + for (auto &&p : joint_init_positions) { req.mutable_refer()->mutable_joint()->push_back(p); } // std::vector joint_positions; KinematicsInverseResp ki_resp; - try - { + try { auto resp = impl_->getInverseKin(req); ki_resp.joint_positions = resp.joint(); - ki_resp.ok = true; - } - catch(std::exception & e) - { + ki_resp.ok = true; + } catch (std::exception &e) { ki_resp.ok = false; return ki_resp; } return ki_resp; - } -CartesianPose Robot::pose_times(const CartesianPose & a, const CartesianPose & b) -{ +CartesianPose Robot::pose_times(const CartesianPose &a, + const CartesianPose &b) { posture::GetPoseTransRequest req; double x = 0.0; - if(a.find("x") != a.end()) - { + if (a.find("x") != a.end()) { x = a.at("x"); } double y = 0.0; - if(a.find("y") != a.end()) - { + if (a.find("y") != a.end()) { y = a.at("y"); } double z = 0.0; - if(a.find("z") != a.end()) - { + if (a.find("z") != a.end()) { z = a.at("z"); } double rx = 0.0; - if(a.find("rx") != a.end()) - { + if (a.find("rx") != a.end()) { rx = a.at("rx"); } double ry = 0.0; - if(a.find("ry") != a.end()) - { + if (a.find("ry") != a.end()) { ry = a.at("ry"); } double rz = 0.0; - if(a.find("rz") != a.end()) - { + if (a.find("rz") != a.end()) { rz = a.at("rz"); } req.mutable_from()->mutable_cart()->mutable_position()->set_x(x); req.mutable_from()->mutable_cart()->mutable_position()->set_y(y); req.mutable_from()->mutable_cart()->mutable_position()->set_z(z); - req.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(rz); - req.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(ry); - req.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(rx); + req.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(rz); + req.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(ry); + req.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(rx); x = 0.0; - if(b.find("x") != b.end()) - { + if (b.find("x") != b.end()) { x = b.at("x"); } y = 0.0; - if(b.find("y") != b.end()) - { + if (b.find("y") != b.end()) { y = b.at("y"); } z = 0.0; - if(b.find("z") != b.end()) - { + if (b.find("z") != b.end()) { z = b.at("z"); } rx = 0.0; - if(b.find("rx") != b.end()) - { + if (b.find("rx") != b.end()) { rx = b.at("rx"); } ry = 0.0; - if(b.find("ry") != b.end()) - { + if (b.find("ry") != b.end()) { ry = b.at("ry"); } rz = 0.0; - if(b.find("rz") != b.end()) - { + if (b.find("rz") != b.end()) { rz = b.at("rz"); } req.mutable_from_to()->mutable_cart()->mutable_position()->set_x(x); req.mutable_from_to()->mutable_cart()->mutable_position()->set_y(y); req.mutable_from_to()->mutable_cart()->mutable_position()->set_z(z); - req.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(rz); - req.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(ry); - req.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(rx); + req.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(rz); + req.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(ry); + req.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(rx); auto resp = impl_->getPoseTrans(req); CartesianPose pose; @@ -1343,46 +1283,51 @@ CartesianPose Robot::pose_times(const CartesianPose & a, const CartesianPose & b return pose; } -CartesianPose Robot::pose_inverse(const CartesianPose & in) -{ +CartesianPose Robot::pose_inverse(const CartesianPose &in) { posture::PoseRequest req; double x = 0.0; - if(in.find("x") != in.end()) - { + if (in.find("x") != in.end()) { x = in.at("x"); } double y = 0.0; - if(in.find("y") != in.end()) - { + if (in.find("y") != in.end()) { y = in.at("y"); } double z = 0.0; - if(in.find("z") != in.end()) - { + if (in.find("z") != in.end()) { z = in.at("z"); } double rx = 0.0; - if(in.find("rx") != in.end()) - { + if (in.find("rx") != in.end()) { rx = in.at("rx"); } double ry = 0.0; - if(in.find("ry") != in.end()) - { + if (in.find("ry") != in.end()) { ry = in.at("ry"); } double rz = 0.0; - if(in.find("rz") != in.end()) - { + if (in.find("rz") != in.end()) { rz = in.at("rz"); } req.mutable_pose()->mutable_cart()->mutable_position()->set_x(x); req.mutable_pose()->mutable_cart()->mutable_position()->set_y(y); req.mutable_pose()->mutable_cart()->mutable_position()->set_z(z); - req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(rz); - req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(ry); - req.mutable_pose()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(rx); + req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(rz); + req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(ry); + req.mutable_pose() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(rx); auto resp = impl_->getPoseInverse(req); CartesianPose pose; pose["x"] = resp.position().x(); @@ -1394,8 +1339,8 @@ CartesianPose Robot::pose_inverse(const CartesianPose & in) return pose; } -void Robot::save_file(const std::string &dir,const std::string &name,bool is_dir,const std::string & data) -{ +void Robot::save_file(const std::string &dir, const std::string &name, + bool is_dir, const std::string &data) { file::SaveFileRequest req; req.set_dir(dir); req.set_name(name); @@ -1406,7 +1351,8 @@ void Robot::save_file(const std::string &dir,const std::string &name,bool is_dir impl_->saveFile(req); } /** -void Robot::save_file(const std::string &dir,const std::string & name,file::File file) +void Robot::save_file(const std::string &dir,const std::string & name,file::File +file) { file::SaveFileRequest req; req.set_dir(dir); @@ -1416,9 +1362,9 @@ void Robot::save_file(const std::string &dir,const std::string & name,file::File } */ - -void Robot::rename_file(const std::string &from_dir,const std::string & from_name,const std::string & to_dir,const std::string & to_name) -{ +void Robot::rename_file(const std::string &from_dir, + const std::string &from_name, const std::string &to_dir, + const std::string &to_name) { file::RenameFileRequest req; file::FileIndex from; file::FileIndex to; @@ -1439,32 +1385,32 @@ void Robot::rename_file(file::FileIndex from,file::FileIndex to) impl_->renameFile(req); } */ -std::tuple Robot::load_file(const std::string &dir,const std::string & name) -{ +std::tuple Robot::load_file(const std::string &dir, + const std::string &name) { file::FileIndex req; req.set_dir(dir); req.set_name(name); file::File resp = impl_->loadFile(req); - std::tuple ret = std::make_tuple(resp.is_dir(),resp.data()); + std::tuple ret = + std::make_tuple(resp.is_dir(), resp.data()); return ret; } -std::vector> Robot::load_file_list(const std::string &dir,const std::string & prefix,const std::string & suffix) -{ +std::vector> Robot::load_file_list( + const std::string &dir, const std::string &prefix, + const std::string &suffix) { file::LoadFileListRequest req; req.set_dir(dir); req.set_prefix(prefix); req.set_suffix(suffix); file::LoadFileListResponse resp = impl_->loadFileList(req); - std::vector> ret; - for(auto f:resp.files()) - { - std::tuple temp = std::make_tuple(f.is_dir(),f.name()); + std::vector> ret; + for (auto f : resp.files()) { + std::tuple temp = std::make_tuple(f.is_dir(), f.name()); ret.push_back(temp); } return ret; } -void Robot::set_payload(double mass, std::map cog) -{ +void Robot::set_payload(double mass, std::map cog) { dynamic::SetPayloadRequest req; req.set_mass(mass); posture::Position c; @@ -1474,14 +1420,12 @@ void Robot::set_payload(double mass, std::map cog) req.set_cog(c); impl_->setPayload(req); } -void Robot::set_payload_mass(double mass) -{ +void Robot::set_payload_mass(double mass) { dynamic::SetMassRequest req; req.set_mass(mass); impl_->setPayload(req); } -void Robot::set_payload_cog(std::map cog) -{ +void Robot::set_payload_cog(std::map cog) { dynamic::SetCogRequest req; posture::Position c; c.set_x(cog.at("x")); @@ -1491,10 +1435,9 @@ void Robot::set_payload_cog(std::map cog) impl_->setPayload(req); } -std::map Robot::get_payload() -{ +std::map Robot::get_payload() { dynamic::Payload resp = impl_->getPayload(); - std::map cog; + std::map cog; cog["x"] = resp.cog().x(); cog["y"] = resp.cog().y(); cog["z"] = resp.cog().z(); @@ -1502,8 +1445,7 @@ std::map Robot::get_payload() return cog; } -void Robot::set_gravity(std::map gravity) -{ +void Robot::set_gravity(std::map gravity) { posture::Position req; req.set_x(gravity.at("x")); req.set_y(gravity.at("y")); @@ -1511,18 +1453,16 @@ void Robot::set_gravity(std::map gravity) impl_->setGravity(req); } -std::map Robot::get_gravity() -{ +std::map Robot::get_gravity() { posture::Position resp = impl_->getGravity(); - std::map gravity; + std::map gravity; gravity["x"] = resp.x(); gravity["y"] = resp.y(); gravity["z"] = resp.z(); return gravity; } -void Robot::set_tcp(std::array tcp) -{ +void Robot::set_tcp(std::array tcp) { posture::CartesianPose req; posture::Position pos; posture::Rotation rot; @@ -1538,8 +1478,7 @@ void Robot::set_tcp(std::array tcp) req.set_rotation(rot); impl_->setTcp(req); } -std::array Robot::get_tcp() -{ +std::array Robot::get_tcp() { posture::CartesianPose resp = impl_->getTcp(); std::array ret; ret[0] = resp.position().x(); @@ -1551,38 +1490,34 @@ std::array Robot::get_tcp() return ret; } -void Robot::set_velocity_factor(int factor) -{ +void Robot::set_velocity_factor(int factor) { kinematic::KinFactor req; req.set_factor(factor); impl_->setKinFactor(req); } -int Robot::get_velocity_factor() -{ +int Robot::get_velocity_factor() { kinematic::KinFactor resp = impl_->getKinFactor(); return resp.factor(); } -CartesianPose Robot::load_tcp(std::string name, std::string dir) -{ +CartesianPose Robot::load_tcp(std::string name, std::string dir) { db::LoadRequest req; req.set_name(name); req.set_dir(dir); - const auto & pose = impl_->loadTcp(req); + const auto &pose = impl_->loadTcp(req); CartesianPose cart_pose; cart_pose["x"] = pose.position().x(); cart_pose["y"] = pose.position().y(); cart_pose["z"] = pose.position().z(); - if(pose.rotation().euler_zyx()) - { + if (pose.rotation().euler_zyx()) { cart_pose["rz"] = pose.rotation().euler_zyx()->z(); cart_pose["ry"] = pose.rotation().euler_zyx()->y(); cart_pose["rx"] = pose.rotation().euler_zyx()->x(); - } + } return cart_pose; } -void Robot::write_single_coil(std::string device, std::string addr, bool value) -{ +void Robot::write_single_coil(std::string device, std::string addr, + bool value) { modbus::SetCoilRequest req; req.set_device(device); req.set_pin(addr); @@ -1590,16 +1525,16 @@ void Robot::write_single_coil(std::string device, std::string addr, bool value) impl_->writeSingleCoil(req); } -void Robot::wirte_multiple_coils(std::string device, std::string addr, std::vector values) -{ +void Robot::wirte_multiple_coils(std::string device, std::string addr, + std::vector values) { modbus::SetCoilsRequest req; req.set_device(device); req.set_pin(addr); req.set_values(values); impl_->writeMultipleCoils(req); } -std::vector Robot::read_coils(std::string device, std::string addr, unsigned int num) -{ +std::vector Robot::read_coils(std::string device, std::string addr, + unsigned int num) { modbus::GetCoilsRequest req; req.set_device(device); req.set_pin(addr); @@ -1607,8 +1542,9 @@ std::vector Robot::read_coils(std::string device, std::string addr, unsign modbus::GetCoilsResponse resp = impl_->readCoils(req); return resp.values(); } -std::vector Robot::read_discrete_inputs(std::string device, std::string addr, unsigned int num) -{ +std::vector Robot::read_discrete_inputs(std::string device, + std::string addr, + unsigned int num) { modbus::GetCoilsRequest req; req.set_device(device); req.set_pin(addr); @@ -1616,16 +1552,16 @@ std::vector Robot::read_discrete_inputs(std::string device, std::string ad modbus::GetCoilsResponse resp = impl_->readDiscreteInputs(req); return resp.values(); } -void Robot::write_single_register(std::string device, std::string addr, unsigned int value) -{ +void Robot::write_single_register(std::string device, std::string addr, + unsigned int value) { modbus::SetRegisterRequest req; req.set_device(device); req.set_pin(addr); req.set_value(value); impl_->writeSingleRegister(req); } -void Robot::write_multiple_registers(std::string device, std::string addr, std::vector values) -{ +void Robot::write_multiple_registers(std::string device, std::string addr, + std::vector values) { modbus::SetRegistersRequest req; req.set_device(device); req.set_pin(addr); @@ -1633,8 +1569,9 @@ void Robot::write_multiple_registers(std::string device, std::string addr, std:: impl_->writeMultipleRegisters(req); } -std::vector Robot::read_holding_registers(std::string device, std::string addr, unsigned int num) -{ +std::vector Robot::read_holding_registers(std::string device, + std::string addr, + unsigned int num) { modbus::GetRegistersRequest req; req.set_device(device); req.set_pin(addr); @@ -1642,8 +1579,9 @@ std::vector Robot::read_holding_registers(std::string device, std: modbus::GetRegistersResponse resp = impl_->readHoldingRegisters(req); return resp.values(); } -std::vector Robot::read_input_registers(std::string device, std::string addr, unsigned int num) -{ +std::vector Robot::read_input_registers(std::string device, + std::string addr, + unsigned int num) { modbus::GetRegistersRequest req; req.set_device(device); req.set_pin(addr); @@ -1666,6 +1604,6 @@ void Robot::set_serial_parity(std::string device, unsigned int parity) { impl_->setSerialParityRequest(req); } -} +} // namespace l_master -} // namespace l_master_sdk +} // namespace lebai diff --git a/sdk/src/robot_impl.cc b/sdk/src/robot_impl.cc index 1140b41..7ce9da4 100644 --- a/sdk/src/robot_impl.cc +++ b/sdk/src/robot_impl.cc @@ -13,645 +13,590 @@ * See the License for the specific language governing permissions and * limitations under the License. */ - -#include "robot_impl.hh" -#include #include #include #include +#include +#include "robot_impl.hh" #include "protos/utils.hh" -namespace lebai -{ - namespace l_master - { - Robot::RobotImpl::RobotImpl(const ::std::string &ip, bool simulator) - { - uint16_t port = simulator ? simulation_port_ : physical_machine_port_; - json_rpc_connector_ = std::make_unique(ip, port); - unsigned int i = 0; - unsigned int count = timeout_ / 0.1; - while (i < count) - { - if (json_rpc_connector_->GetConnectionStatus() == JSONRpcConnector::kOpen) - { - break; - } - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - i++; - } - } - Robot::RobotImpl::~RobotImpl() {} - - std::tuple Robot::RobotImpl::call(const std::string &method, const std::string &req_data_str) - { - // std::string jsonrpc_req = ToJSONRpcReqString(++jsonrpc_id_, method, params); - std::string resp_data_str; - auto ret = json_rpc_connector_->CallRpc(method, req_data_str, &resp_data_str); - // std::string resp_data; - // if(ExtractJSONRpcRespString(jsonrpc_resp, resp_id, resp_data) < 0) - // { - // return std::make_tuple(-1, ""); - // } - return std::make_tuple(ret, resp_data_str); - } - - bool Robot::RobotImpl::isNetworkConnected() - { - // return json_rpc_connector_->Ping(); - return json_rpc_connector_->GetConnectionStatus() == JSONRpcConnector::kOpen; - } - - int Robot::RobotImpl::startSys() - { - return json_rpc_connector_->CallRpc("start_sys", "{}", nullptr); - } - - int Robot::RobotImpl::stopSys() - { - return json_rpc_connector_->CallRpc("stop_sys", "{}", nullptr); - } - - int Robot::RobotImpl::powerdown() - { - return json_rpc_connector_->CallRpc("powerdown", "{}", nullptr); - } - - int Robot::RobotImpl::stop() - { - return json_rpc_connector_->CallRpc("stop", "{}", nullptr); - } - - int Robot::RobotImpl::estop() - { - return json_rpc_connector_->CallRpc("estop", "{}", nullptr); - } - - int Robot::RobotImpl::teachMode() - { - return json_rpc_connector_->CallRpc("start_teach_mode", "{}", nullptr); - } - - int Robot::RobotImpl::endTeachMode() - { - return json_rpc_connector_->CallRpc("end_teach_mode", "{}", nullptr); - } - - int Robot::RobotImpl::pause() - { - return json_rpc_connector_->CallRpc("pause", "{}", nullptr); - } - - int Robot::RobotImpl::resume() - { - return json_rpc_connector_->CallRpc("resume", "{}", nullptr); - } - - void Robot::RobotImpl::reboot() - { - json_rpc_connector_->CallRpc("reboot", "{}", nullptr); - } - - motion::MotionIndex Robot::RobotImpl::moveJoint(const motion::MoveRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("move_joint", req.ToJSONString(), &resp); - motion::MotionIndex motion_resp; - motion_resp.FromJSONString(resp); - return motion_resp; - } - motion::MotionIndex Robot::RobotImpl::moveLinear(const motion::MoveRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("move_linear", req.ToJSONString(), &resp); - motion::MotionIndex motion_resp; - motion_resp.FromJSONString(resp); - return motion_resp; - } - motion::MotionIndex Robot::RobotImpl::moveCircular(const motion::MovecRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("move_circular", req.ToJSONString(), &resp); - motion::MotionIndex motion_resp; - motion_resp.FromJSONString(resp); - return motion_resp; - } - motion::MotionIndex Robot::RobotImpl::towardJoint(const motion::MoveRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("toward_joint", req.ToJSONString(), &resp); - motion::MotionIndex motion_resp; - motion_resp.FromJSONString(resp); - return motion_resp; - } - motion::MotionIndex Robot::RobotImpl::speedJoint(const motion::SpeedJRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("speed_joint", req.ToJSONString(), &resp); - motion::MotionIndex motion_resp; - motion_resp.FromJSONString(resp); - return motion_resp; - } - motion::MotionIndex Robot::RobotImpl::speedLinear(const motion::SpeedLRequest &req) - { - std::string resp; - - auto req_string = req.ToJSONString(); - std::cout << "req " << req_string << "\n"; - json_rpc_connector_->CallRpc("speed_linear", req_string, &resp); - // json_rpc_connector_->CallRpc("speed_linear",req.ToJSONString(),&resp); - motion::MotionIndex motion_resp; - motion_resp.FromJSONString(resp); - std::cout << "resp " << resp << "\n"; - return motion_resp; - } - void Robot::RobotImpl::movePvat(const motion::MovePvatRequest &req) - { - json_rpc_connector_->CallRpc("move_pvat", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::waitMove(const motion::MotionIndex &req) - { - std::string resp; - json_rpc_connector_->CallRpc("wait_move", req.ToJSONString(), &resp); - // std::cout<<"resp " << resp << std::endl; - } - motion::MotionIndex Robot::RobotImpl::getRunningMotion() - { - std::string resp; - json_rpc_connector_->CallRpc("get_running_motion", "{}", &resp); - motion::MotionIndex get_running_motion_resp; - get_running_motion_resp.FromJSONString(resp); - return get_running_motion_resp; - } - motion::GetMotionStateResponse Robot::RobotImpl::getMotionState(const motion::MotionIndex &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_motion_state", req.ToJSONString(), &resp); - motion::GetMotionStateResponse get_motion_state_resp; - get_motion_state_resp.FromJSONString(resp); - return get_motion_state_resp; - } - void Robot::RobotImpl::stopMove() - { - json_rpc_connector_->CallRpc("stop_move", "{}", nullptr); - } - system::RobotState Robot::RobotImpl::getRobotState() - { - std::string resp; - json_rpc_connector_->CallRpc("get_robot_state", "{}", &resp); - system::GetRobotStateResponse get_robot_state_resp; - get_robot_state_resp.FromJSONString(resp); - return get_robot_state_resp.state(); - } - - system::EstopReason Robot::RobotImpl::getEstopReason() - { - std::string resp; - json_rpc_connector_->CallRpc("get_estop_reason", "{}", &resp); - system::GetEstopReasonResponse get_estop_reason_resp; - get_estop_reason_resp.FromJSONString(resp); - return get_estop_reason_resp.reason(); - } - - system::PhyData Robot::RobotImpl::getPhyData() - { - std::string resp; - json_rpc_connector_->CallRpc("get_phy_data", "{}", &resp); - // std::cout<<"resp "<CallRpc("get_kin_data", "{}", &resp); - // std::cout<<"resp "<CallRpc("get_di", req.ToJSONString(), &resp); - io::GetDioPinResponse get_dio_resp; - get_dio_resp.FromJSONString(resp); - return get_dio_resp; - } - io::GetDioPinsResponse Robot::RobotImpl::getDIS(const io::GetDioPinsRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_dis", req.ToJSONString(), &resp_str); - io::GetDioPinsResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - io::GetDioPinResponse Robot::RobotImpl::getDO(const io::GetDioPinRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_do", req.ToJSONString(), &resp); - io::GetDioPinResponse get_dio_resp; - get_dio_resp.FromJSONString(resp); - return get_dio_resp; - } - io::GetDioPinsResponse Robot::RobotImpl::getDOS(const io::GetDioPinsRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_dos", req.ToJSONString(), &resp_str); - io::GetDioPinsResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - - void Robot::RobotImpl::setDO(const io::SetDoPinRequest &req) - { - json_rpc_connector_->CallRpc("set_do", req.ToJSONString(), nullptr); - return; - } - - io::GetAioPinResponse Robot::RobotImpl::getAI(const io::GetAioPinRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_ai", req.ToJSONString(), &resp); - io::GetAioPinResponse get_aio_resp; - get_aio_resp.FromJSONString(resp); - return get_aio_resp; - } - io::GetAioPinsResponse Robot::RobotImpl::getAIS(const io::GetAioPinsRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_ais", req.ToJSONString(), &resp); - io::GetAioPinsResponse get_aio_resp; - get_aio_resp.FromJSONString(resp); - return get_aio_resp; - } - io::GetAioPinResponse Robot::RobotImpl::getAO(const io::GetAioPinRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_ao", req.ToJSONString(), &resp); - io::GetAioPinResponse get_aio_resp; - get_aio_resp.FromJSONString(resp); - return get_aio_resp; - } - io::GetAioPinsResponse Robot::RobotImpl::getAOS(const io::GetAioPinsRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_aos", req.ToJSONString(), &resp); - io::GetAioPinsResponse get_aio_resp; - get_aio_resp.FromJSONString(resp); - return get_aio_resp; - } - void Robot::RobotImpl::setDioMode(const io::SetDioModeRequest &req) - { - json_rpc_connector_->CallRpc("set_dio_mode", req.ToJSONString(), nullptr); - } - io::GetDiosModeResponse Robot::RobotImpl::getDiosMode(const io::GetDiosModeRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_dios_mode", req.ToJSONString(), &resp); - io::GetDiosModeResponse resp_; - resp_.FromJSONString(resp); - return resp_; - } - - void Robot::RobotImpl::setAO(const io::SetAoPinRequest &req) - { - json_rpc_connector_->CallRpc("set_ao", req.ToJSONString(), nullptr); - return; - } - - void Robot::RobotImpl::setClaw(const claw::SetClawRequest &req) - { - json_rpc_connector_->CallRpc("set_claw", req.ToJSONString(), nullptr); - return; - } - claw::Claw Robot::RobotImpl::getClaw() - { - std::string resp; - json_rpc_connector_->CallRpc("get_claw", "{}", &resp); - claw::Claw get_claw_resp; - get_claw_resp.FromJSONString(resp); - return get_claw_resp; - } - - void Robot::RobotImpl::setLed(const led::LedData &req) - { - json_rpc_connector_->CallRpc("set_led", req.ToJSONString(), nullptr); - } - - void Robot::RobotImpl::setVoice(const led::VoiceData &req) - { - json_rpc_connector_->CallRpc("set_voice", req.ToJSONString(), nullptr); - } - - void Robot::RobotImpl::setFan(const led::FanData &req) - { - json_rpc_connector_->CallRpc("set_fan", req.ToJSONString(), nullptr); - } - - void Robot::RobotImpl::setSignal(const signal::SetSignalRequest &req) - { - json_rpc_connector_->CallRpc("set_signal", req.ToJSONString(), nullptr); - } - signal::GetSignalResponse Robot::RobotImpl::getSignal(const signal::GetSignalRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_signal", req.ToJSONString(), &resp); - signal::GetSignalResponse set_signal_resp; - set_signal_resp.FromJSONString(resp); - return set_signal_resp; - } - void Robot::RobotImpl::addSignal(const signal::SetSignalRequest &req) - { - json_rpc_connector_->CallRpc("add_signal", req.ToJSONString(), nullptr); - } - - control::TaskIndex Robot::RobotImpl::scene(const control::StartTaskRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("start_task", req.ToJSONString(), &resp); - control::TaskIndex start_task_resp; - start_task_resp.FromJSONString(resp); - return start_task_resp; - } - - control::TaskIds Robot::RobotImpl::loadTaskList() - { - std::string resp; - json_rpc_connector_->CallRpc("load_task_list", "{}", &resp); - control::TaskIds list_resp; - list_resp.FromJSONString(resp); - return list_resp; - } - - void Robot::RobotImpl::pauseTask(const control::PauseRequest &req) - { - json_rpc_connector_->CallRpc("pause_task", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::resumeTask(const control::TaskIndex &req) - { - json_rpc_connector_->CallRpc("resume_task", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::cancelTask(const control::TaskIndex &req) - { - json_rpc_connector_->CallRpc("cancel_task", req.ToJSONString(), nullptr); - } - control::HookResponse Robot::RobotImpl::execHook(const control::Exec &req) - { - std::string resp; - json_rpc_connector_->CallRpc("exec_hook", req.ToJSONString(), &resp); - control::HookResponse hook_resp; - hook_resp.FromJSONString(resp); - return hook_resp; - } - control::Task Robot::RobotImpl::loadTask(const control::TaskIndex &req) - { - std::string resp; - json_rpc_connector_->CallRpc("load_task", req.ToJSONString(), &resp); - control::Task task_resp; - task_resp.FromJSONString(resp); - return task_resp; - } - control::Task Robot::RobotImpl::loadTask() - { - std::string resp; - json_rpc_connector_->CallRpc("load_task", "{}", &resp); - control::Task task_resp; - task_resp.FromJSONString(resp); - return task_resp; - } - - posture::CartesianPose Robot::RobotImpl::getForwardKin(const posture::PoseRequest &req) - { - std::string resp; - json_rpc_connector_->CallRpc("get_forward_kin", req.ToJSONString(), &resp); - posture::CartesianPose get_forward_kin_resp; - get_forward_kin_resp.FromJSONString(resp); - return get_forward_kin_resp; - } - - posture::JointPose Robot::RobotImpl::getInverseKin( - const posture::GetInverseKinRequest &req) - { - std::string resp; - if (json_rpc_connector_->CallRpc("get_inverse_kin", req.ToJSONString(), &resp) < 0) - { - throw std::runtime_error("get_inverse_kin failed"); - } - posture::JointPose get_inverse_kin_resp; - get_inverse_kin_resp.FromJSONString(resp); - return get_inverse_kin_resp; - } - - posture::CartesianPose Robot::RobotImpl::getPoseTrans(const posture::GetPoseTransRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_pose_trans", req.ToJSONString(), &resp_str); - posture::CartesianPose resp; - resp.FromJSONString(resp_str); - return resp; - } - posture::CartesianPose Robot::RobotImpl::getPoseInverse(const posture::PoseRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_pose_inverse", req.ToJSONString(), &resp_str); - posture::CartesianPose resp; - resp.FromJSONString(resp_str); - return resp; - } - - void Robot::RobotImpl::saveFile(const file::SaveFileRequest &req) - { - json_rpc_connector_->CallRpc("save_file", req.ToJSONString(), nullptr); - } - - void Robot::RobotImpl::renameFile(const file::RenameFileRequest &req) - { - json_rpc_connector_->CallRpc("rename_file", req.ToJSONString(), nullptr); - } - - file::File Robot::RobotImpl::loadFile(const file::FileIndex &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("load_file", req.ToJSONString(), &resp_str); - file::File resp; - resp.FromJSONString(resp_str); - return resp; - } - - file::LoadFileListResponse Robot::RobotImpl::loadFileList(const file::LoadFileListRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("load_file_list", req.ToJSONString(), &resp_str); - file::LoadFileListResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - - void Robot::RobotImpl::zip(const file::ZipRequest &req) - { - json_rpc_connector_->CallRpc("zip", req.ToJSONString(), nullptr); - } - - void Robot::RobotImpl::unzip(const file::UnzipRequest &req) - { - json_rpc_connector_->CallRpc("unzip", req.ToJSONString(), nullptr); - } - - file::LoadZipListResponse Robot::RobotImpl::loadZipList(const file::LoadZipListRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("load_zip_list", req.ToJSONString(), &resp_str); - file::LoadZipListResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - - void Robot::RobotImpl::setPayload(const dynamic::SetPayloadRequest &req) - { - json_rpc_connector_->CallRpc("set_payload", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::setPayload(const dynamic::SetCogRequest &req) - { - json_rpc_connector_->CallRpc("set_payload", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::setPayload(const dynamic::SetMassRequest &req) - { - json_rpc_connector_->CallRpc("set_payload", req.ToJSONString(), nullptr); - } - dynamic::Payload Robot::RobotImpl::getPayload() - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_payload", "{}", &resp_str); - dynamic::Payload resp; - resp.FromJSONString(resp_str); - return resp; - } - void Robot::RobotImpl::setGravity(const posture::Position &req) - { - json_rpc_connector_->CallRpc("set_gravity", req.ToJSONString(), nullptr); - } - posture::Position Robot::RobotImpl::getGravity() - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_gravity", "{}", &resp_str); - posture::Position resp; - resp.FromJSONString(resp_str); - return resp; - } - void Robot::RobotImpl::savePayload(const dynamic::SavePayloadRequest &req) - { - json_rpc_connector_->CallRpc("save_payload", req.ToJSONString(), nullptr); - } - dynamic::Payload Robot::RobotImpl::loadPayload(const db::LoadRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("load_payload", req.ToJSONString(), &resp_str); - dynamic::Payload resp; - resp.FromJSONString(resp_str); - return resp; - } - db::LoadListResponse Robot::RobotImpl::loadPayloadList(const db::LoadListRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("load_payload_list", req.ToJSONString(), &resp_str); - db::LoadListResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - - void Robot::RobotImpl::setTcp(const posture::CartesianPose &req) - { - json_rpc_connector_->CallRpc("set_tcp", req.ToJSONString(), nullptr); - } - posture::CartesianPose Robot::RobotImpl::getTcp() - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_tcp", "{}", &resp_str); - posture::CartesianPose resp; - resp.FromJSONString(resp_str); - return resp; - } - void Robot::RobotImpl::setKinFactor(const kinematic::KinFactor &req) - { - json_rpc_connector_->CallRpc("set_kin_factor", req.ToJSONString(), nullptr); - } - kinematic::KinFactor Robot::RobotImpl::getKinFactor() - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_kin_factor", "{}", &resp_str); - kinematic::KinFactor resp; - resp.FromJSONString(resp_str); - return resp; - } - posture::CartesianPose Robot::RobotImpl::loadTcp(const db::LoadRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("get_tcp", req.ToJSONString(), &resp_str); - posture::CartesianPose resp; - resp.FromJSONString(resp_str); - return resp; - } - void Robot::RobotImpl::writeSingleCoil(const modbus::SetCoilRequest &req) - { - json_rpc_connector_->CallRpc("write_single_coil", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::writeMultipleCoils(const modbus::SetCoilsRequest &req) - { - json_rpc_connector_->CallRpc("write_multiple_coils", req.ToJSONString(), nullptr); - } - modbus::GetCoilsResponse Robot::RobotImpl::readCoils(const modbus::GetCoilsRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("read_coils", req.ToJSONString(), &resp_str); - modbus::GetCoilsResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - modbus::GetCoilsResponse Robot::RobotImpl::readDiscreteInputs(const modbus::GetCoilsRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("read_discrete_inputs", req.ToJSONString(), &resp_str); - modbus::GetCoilsResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - void Robot::RobotImpl::writeSingleRegister(const modbus::SetRegisterRequest &req) - { - json_rpc_connector_->CallRpc("write_single_register", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::writeMultipleRegisters(const modbus::SetRegistersRequest &req) - { - json_rpc_connector_->CallRpc("write_multiple_registers", req.ToJSONString(), nullptr); - } - modbus::GetRegistersResponse Robot::RobotImpl::readInputRegisters(const modbus::GetRegistersRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("read_input_registers", req.ToJSONString(), &resp_str); - modbus::GetRegistersResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - modbus::GetRegistersResponse Robot::RobotImpl::readHoldingRegisters(const modbus::GetRegistersRequest &req) - { - std::string resp_str; - json_rpc_connector_->CallRpc("read_holding_registers", req.ToJSONString(), &resp_str); - modbus::GetRegistersResponse resp; - resp.FromJSONString(resp_str); - return resp; - } - - void Robot::RobotImpl::setSerialBaudRateRequest(const serial::SetSerialBaudRateRequest &req) - { - json_rpc_connector_->CallRpc("set_serial_baud_rate", req.ToJSONString(), nullptr); - } - void Robot::RobotImpl::setSerialParityRequest(const serial::SetSerialParityRequest &req) - { - json_rpc_connector_->CallRpc("set_serial_parity", req.ToJSONString(), nullptr); - } - +namespace lebai { +namespace l_master { +Robot::RobotImpl::RobotImpl(const ::std::string &ip, bool simulator) { + uint16_t port = simulator ? simulation_port_ : physical_machine_port_; + json_rpc_connector_ = std::make_unique(ip, port); + unsigned int i = 0; + unsigned int count = timeout_ / 0.1; + while (i < count) { + if (json_rpc_connector_->GetConnectionStatus() == JSONRpcConnector::kOpen) { + break; + } + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + i++; + } +} +Robot::RobotImpl::~RobotImpl() {} + +std::tuple Robot::RobotImpl::call( + const std::string &method, const std::string &req_data_str) { + // std::string jsonrpc_req = ToJSONRpcReqString(++jsonrpc_id_, method, + // params); + std::string resp_data_str; + auto ret = json_rpc_connector_->CallRpc(method, req_data_str, &resp_data_str); + // std::string resp_data; + // if(ExtractJSONRpcRespString(jsonrpc_resp, resp_id, resp_data) < 0) + // { + // return std::make_tuple(-1, ""); + // } + return std::make_tuple(ret, resp_data_str); +} + +bool Robot::RobotImpl::isNetworkConnected() { + // return json_rpc_connector_->Ping(); + return json_rpc_connector_->GetConnectionStatus() == JSONRpcConnector::kOpen; +} + +int Robot::RobotImpl::startSys() { + return json_rpc_connector_->CallRpc("start_sys", "{}", nullptr); +} + +int Robot::RobotImpl::stopSys() { + return json_rpc_connector_->CallRpc("stop_sys", "{}", nullptr); +} + +int Robot::RobotImpl::powerdown() { + return json_rpc_connector_->CallRpc("powerdown", "{}", nullptr); +} + +int Robot::RobotImpl::stop() { + return json_rpc_connector_->CallRpc("stop", "{}", nullptr); +} + +int Robot::RobotImpl::estop() { + return json_rpc_connector_->CallRpc("estop", "{}", nullptr); +} + +int Robot::RobotImpl::teachMode() { + return json_rpc_connector_->CallRpc("start_teach_mode", "{}", nullptr); +} + +int Robot::RobotImpl::endTeachMode() { + return json_rpc_connector_->CallRpc("end_teach_mode", "{}", nullptr); +} + +int Robot::RobotImpl::pause() { + return json_rpc_connector_->CallRpc("pause", "{}", nullptr); +} + +int Robot::RobotImpl::resume() { + return json_rpc_connector_->CallRpc("resume", "{}", nullptr); +} + +void Robot::RobotImpl::reboot() { + json_rpc_connector_->CallRpc("reboot", "{}", nullptr); +} + +motion::MotionIndex Robot::RobotImpl::moveJoint( + const motion::MoveRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("move_joint", req.ToJSONString(), &resp); + motion::MotionIndex motion_resp; + motion_resp.FromJSONString(resp); + return motion_resp; +} +motion::MotionIndex Robot::RobotImpl::moveLinear( + const motion::MoveRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("move_linear", req.ToJSONString(), &resp); + motion::MotionIndex motion_resp; + motion_resp.FromJSONString(resp); + return motion_resp; +} +motion::MotionIndex Robot::RobotImpl::moveCircular( + const motion::MovecRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("move_circular", req.ToJSONString(), &resp); + motion::MotionIndex motion_resp; + motion_resp.FromJSONString(resp); + return motion_resp; +} +motion::MotionIndex Robot::RobotImpl::towardJoint( + const motion::MoveRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("toward_joint", req.ToJSONString(), &resp); + motion::MotionIndex motion_resp; + motion_resp.FromJSONString(resp); + return motion_resp; +} +motion::MotionIndex Robot::RobotImpl::speedJoint( + const motion::SpeedJRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("speed_joint", req.ToJSONString(), &resp); + motion::MotionIndex motion_resp; + motion_resp.FromJSONString(resp); + return motion_resp; +} +motion::MotionIndex Robot::RobotImpl::speedLinear( + const motion::SpeedLRequest &req) { + std::string resp; + + auto req_string = req.ToJSONString(); + std::cout << "req " << req_string << "\n"; + json_rpc_connector_->CallRpc("speed_linear", req_string, &resp); + // json_rpc_connector_->CallRpc("speed_linear",req.ToJSONString(),&resp); + motion::MotionIndex motion_resp; + motion_resp.FromJSONString(resp); + std::cout << "resp " << resp << "\n"; + return motion_resp; +} +void Robot::RobotImpl::movePvat(const motion::MovePvatRequest &req) { + json_rpc_connector_->CallRpc("move_pvat", req.ToJSONString(), nullptr); +} +void Robot::RobotImpl::waitMove(const motion::MotionIndex &req) { + std::string resp; + json_rpc_connector_->CallRpc("wait_move", req.ToJSONString(), &resp); + // std::cout<<"resp " << resp << std::endl; +} +motion::MotionIndex Robot::RobotImpl::getRunningMotion() { + std::string resp; + json_rpc_connector_->CallRpc("get_running_motion", "{}", &resp); + motion::MotionIndex get_running_motion_resp; + get_running_motion_resp.FromJSONString(resp); + return get_running_motion_resp; +} +motion::GetMotionStateResponse Robot::RobotImpl::getMotionState( + const motion::MotionIndex &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_motion_state", req.ToJSONString(), &resp); + motion::GetMotionStateResponse get_motion_state_resp; + get_motion_state_resp.FromJSONString(resp); + return get_motion_state_resp; +} +void Robot::RobotImpl::stopMove() { + json_rpc_connector_->CallRpc("stop_move", "{}", nullptr); +} +system::RobotState Robot::RobotImpl::getRobotState() { + std::string resp; + json_rpc_connector_->CallRpc("get_robot_state", "{}", &resp); + system::GetRobotStateResponse get_robot_state_resp; + get_robot_state_resp.FromJSONString(resp); + return get_robot_state_resp.state(); +} + +system::EstopReason Robot::RobotImpl::getEstopReason() { + std::string resp; + json_rpc_connector_->CallRpc("get_estop_reason", "{}", &resp); + system::GetEstopReasonResponse get_estop_reason_resp; + get_estop_reason_resp.FromJSONString(resp); + return get_estop_reason_resp.reason(); +} + +system::PhyData Robot::RobotImpl::getPhyData() { + std::string resp; + json_rpc_connector_->CallRpc("get_phy_data", "{}", &resp); + // std::cout<<"resp "<CallRpc("get_kin_data", "{}", &resp); + // std::cout<<"resp "<CallRpc("get_di", req.ToJSONString(), &resp); + io::GetDioPinResponse get_dio_resp; + get_dio_resp.FromJSONString(resp); + return get_dio_resp; +} +io::GetDioPinsResponse Robot::RobotImpl::getDIS( + const io::GetDioPinsRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("get_dis", req.ToJSONString(), &resp_str); + io::GetDioPinsResponse resp; + resp.FromJSONString(resp_str); + return resp; +} +io::GetDioPinResponse Robot::RobotImpl::getDO(const io::GetDioPinRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_do", req.ToJSONString(), &resp); + io::GetDioPinResponse get_dio_resp; + get_dio_resp.FromJSONString(resp); + return get_dio_resp; +} +io::GetDioPinsResponse Robot::RobotImpl::getDOS( + const io::GetDioPinsRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("get_dos", req.ToJSONString(), &resp_str); + io::GetDioPinsResponse resp; + resp.FromJSONString(resp_str); + return resp; +} + +void Robot::RobotImpl::setDO(const io::SetDoPinRequest &req) { + json_rpc_connector_->CallRpc("set_do", req.ToJSONString(), nullptr); + return; +} + +io::GetAioPinResponse Robot::RobotImpl::getAI(const io::GetAioPinRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_ai", req.ToJSONString(), &resp); + io::GetAioPinResponse get_aio_resp; + get_aio_resp.FromJSONString(resp); + return get_aio_resp; +} +io::GetAioPinsResponse Robot::RobotImpl::getAIS( + const io::GetAioPinsRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_ais", req.ToJSONString(), &resp); + io::GetAioPinsResponse get_aio_resp; + get_aio_resp.FromJSONString(resp); + return get_aio_resp; +} +io::GetAioPinResponse Robot::RobotImpl::getAO(const io::GetAioPinRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_ao", req.ToJSONString(), &resp); + io::GetAioPinResponse get_aio_resp; + get_aio_resp.FromJSONString(resp); + return get_aio_resp; +} +io::GetAioPinsResponse Robot::RobotImpl::getAOS( + const io::GetAioPinsRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_aos", req.ToJSONString(), &resp); + io::GetAioPinsResponse get_aio_resp; + get_aio_resp.FromJSONString(resp); + return get_aio_resp; +} +void Robot::RobotImpl::setDioMode(const io::SetDioModeRequest &req) { + json_rpc_connector_->CallRpc("set_dio_mode", req.ToJSONString(), nullptr); +} +io::GetDiosModeResponse Robot::RobotImpl::getDiosMode( + const io::GetDiosModeRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_dios_mode", req.ToJSONString(), &resp); + io::GetDiosModeResponse resp_; + resp_.FromJSONString(resp); + return resp_; +} + +void Robot::RobotImpl::setAO(const io::SetAoPinRequest &req) { + json_rpc_connector_->CallRpc("set_ao", req.ToJSONString(), nullptr); + return; +} + +void Robot::RobotImpl::setClaw(const claw::SetClawRequest &req) { + json_rpc_connector_->CallRpc("set_claw", req.ToJSONString(), nullptr); + return; +} +claw::Claw Robot::RobotImpl::getClaw() { + std::string resp; + json_rpc_connector_->CallRpc("get_claw", "{}", &resp); + claw::Claw get_claw_resp; + get_claw_resp.FromJSONString(resp); + return get_claw_resp; +} + +void Robot::RobotImpl::setLed(const led::LedData &req) { + json_rpc_connector_->CallRpc("set_led", req.ToJSONString(), nullptr); +} + +void Robot::RobotImpl::setVoice(const led::VoiceData &req) { + json_rpc_connector_->CallRpc("set_voice", req.ToJSONString(), nullptr); +} + +void Robot::RobotImpl::setFan(const led::FanData &req) { + json_rpc_connector_->CallRpc("set_fan", req.ToJSONString(), nullptr); +} + +void Robot::RobotImpl::setSignal(const signal::SetSignalRequest &req) { + json_rpc_connector_->CallRpc("set_signal", req.ToJSONString(), nullptr); +} +signal::GetSignalResponse Robot::RobotImpl::getSignal( + const signal::GetSignalRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_signal", req.ToJSONString(), &resp); + signal::GetSignalResponse set_signal_resp; + set_signal_resp.FromJSONString(resp); + return set_signal_resp; +} +void Robot::RobotImpl::addSignal(const signal::SetSignalRequest &req) { + json_rpc_connector_->CallRpc("add_signal", req.ToJSONString(), nullptr); +} + +control::TaskIndex Robot::RobotImpl::scene( + const control::StartTaskRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("start_task", req.ToJSONString(), &resp); + control::TaskIndex start_task_resp; + start_task_resp.FromJSONString(resp); + return start_task_resp; +} + +control::TaskIds Robot::RobotImpl::loadTaskList() { + std::string resp; + json_rpc_connector_->CallRpc("load_task_list", "{}", &resp); + control::TaskIds list_resp; + list_resp.FromJSONString(resp); + return list_resp; +} + +void Robot::RobotImpl::pauseTask(const control::PauseRequest &req) { + json_rpc_connector_->CallRpc("pause_task", req.ToJSONString(), nullptr); +} +void Robot::RobotImpl::resumeTask(const control::TaskIndex &req) { + json_rpc_connector_->CallRpc("resume_task", req.ToJSONString(), nullptr); +} +void Robot::RobotImpl::cancelTask(const control::TaskIndex &req) { + json_rpc_connector_->CallRpc("cancel_task", req.ToJSONString(), nullptr); +} +control::HookResponse Robot::RobotImpl::execHook(const control::Exec &req) { + std::string resp; + json_rpc_connector_->CallRpc("exec_hook", req.ToJSONString(), &resp); + control::HookResponse hook_resp; + hook_resp.FromJSONString(resp); + return hook_resp; +} +control::Task Robot::RobotImpl::loadTask(const control::TaskIndex &req) { + std::string resp; + json_rpc_connector_->CallRpc("load_task", req.ToJSONString(), &resp); + control::Task task_resp; + task_resp.FromJSONString(resp); + return task_resp; +} +control::Task Robot::RobotImpl::loadTask() { + std::string resp; + json_rpc_connector_->CallRpc("load_task", "{}", &resp); + control::Task task_resp; + task_resp.FromJSONString(resp); + return task_resp; +} + +posture::CartesianPose Robot::RobotImpl::getForwardKin( + const posture::PoseRequest &req) { + std::string resp; + json_rpc_connector_->CallRpc("get_forward_kin", req.ToJSONString(), &resp); + posture::CartesianPose get_forward_kin_resp; + get_forward_kin_resp.FromJSONString(resp); + return get_forward_kin_resp; +} + +posture::JointPose Robot::RobotImpl::getInverseKin( + const posture::GetInverseKinRequest &req) { + std::string resp; + if (json_rpc_connector_->CallRpc("get_inverse_kin", req.ToJSONString(), + &resp) < 0) { + throw std::runtime_error("get_inverse_kin failed"); } -} \ No newline at end of file + posture::JointPose get_inverse_kin_resp; + get_inverse_kin_resp.FromJSONString(resp); + return get_inverse_kin_resp; +} + +posture::CartesianPose Robot::RobotImpl::getPoseTrans( + const posture::GetPoseTransRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("get_pose_trans", req.ToJSONString(), &resp_str); + posture::CartesianPose resp; + resp.FromJSONString(resp_str); + return resp; +} +posture::CartesianPose Robot::RobotImpl::getPoseInverse( + const posture::PoseRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("get_pose_inverse", req.ToJSONString(), + &resp_str); + posture::CartesianPose resp; + resp.FromJSONString(resp_str); + return resp; +} + +void Robot::RobotImpl::saveFile(const file::SaveFileRequest &req) { + json_rpc_connector_->CallRpc("save_file", req.ToJSONString(), nullptr); +} + +void Robot::RobotImpl::renameFile(const file::RenameFileRequest &req) { + json_rpc_connector_->CallRpc("rename_file", req.ToJSONString(), nullptr); +} + +file::File Robot::RobotImpl::loadFile(const file::FileIndex &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("load_file", req.ToJSONString(), &resp_str); + file::File resp; + resp.FromJSONString(resp_str); + return resp; +} + +file::LoadFileListResponse Robot::RobotImpl::loadFileList( + const file::LoadFileListRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("load_file_list", req.ToJSONString(), &resp_str); + file::LoadFileListResponse resp; + resp.FromJSONString(resp_str); + return resp; +} + +void Robot::RobotImpl::zip(const file::ZipRequest &req) { + json_rpc_connector_->CallRpc("zip", req.ToJSONString(), nullptr); +} + +void Robot::RobotImpl::unzip(const file::UnzipRequest &req) { + json_rpc_connector_->CallRpc("unzip", req.ToJSONString(), nullptr); +} + +file::LoadZipListResponse Robot::RobotImpl::loadZipList( + const file::LoadZipListRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("load_zip_list", req.ToJSONString(), &resp_str); + file::LoadZipListResponse resp; + resp.FromJSONString(resp_str); + return resp; +} + +void Robot::RobotImpl::setPayload(const dynamic::SetPayloadRequest &req) { + json_rpc_connector_->CallRpc("set_payload", req.ToJSONString(), nullptr); +} +void Robot::RobotImpl::setPayload(const dynamic::SetCogRequest &req) { + json_rpc_connector_->CallRpc("set_payload", req.ToJSONString(), nullptr); +} +void Robot::RobotImpl::setPayload(const dynamic::SetMassRequest &req) { + json_rpc_connector_->CallRpc("set_payload", req.ToJSONString(), nullptr); +} +dynamic::Payload Robot::RobotImpl::getPayload() { + std::string resp_str; + json_rpc_connector_->CallRpc("get_payload", "{}", &resp_str); + dynamic::Payload resp; + resp.FromJSONString(resp_str); + return resp; +} +void Robot::RobotImpl::setGravity(const posture::Position &req) { + json_rpc_connector_->CallRpc("set_gravity", req.ToJSONString(), nullptr); +} +posture::Position Robot::RobotImpl::getGravity() { + std::string resp_str; + json_rpc_connector_->CallRpc("get_gravity", "{}", &resp_str); + posture::Position resp; + resp.FromJSONString(resp_str); + return resp; +} +void Robot::RobotImpl::savePayload(const dynamic::SavePayloadRequest &req) { + json_rpc_connector_->CallRpc("save_payload", req.ToJSONString(), nullptr); +} +dynamic::Payload Robot::RobotImpl::loadPayload(const db::LoadRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("load_payload", req.ToJSONString(), &resp_str); + dynamic::Payload resp; + resp.FromJSONString(resp_str); + return resp; +} +db::LoadListResponse Robot::RobotImpl::loadPayloadList( + const db::LoadListRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("load_payload_list", req.ToJSONString(), + &resp_str); + db::LoadListResponse resp; + resp.FromJSONString(resp_str); + return resp; +} + +void Robot::RobotImpl::setTcp(const posture::CartesianPose &req) { + json_rpc_connector_->CallRpc("set_tcp", req.ToJSONString(), nullptr); +} +posture::CartesianPose Robot::RobotImpl::getTcp() { + std::string resp_str; + json_rpc_connector_->CallRpc("get_tcp", "{}", &resp_str); + posture::CartesianPose resp; + resp.FromJSONString(resp_str); + return resp; +} +void Robot::RobotImpl::setKinFactor(const kinematic::KinFactor &req) { + json_rpc_connector_->CallRpc("set_kin_factor", req.ToJSONString(), nullptr); +} +kinematic::KinFactor Robot::RobotImpl::getKinFactor() { + std::string resp_str; + json_rpc_connector_->CallRpc("get_kin_factor", "{}", &resp_str); + kinematic::KinFactor resp; + resp.FromJSONString(resp_str); + return resp; +} +posture::CartesianPose Robot::RobotImpl::loadTcp(const db::LoadRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("get_tcp", req.ToJSONString(), &resp_str); + posture::CartesianPose resp; + resp.FromJSONString(resp_str); + return resp; +} +void Robot::RobotImpl::writeSingleCoil(const modbus::SetCoilRequest &req) { + json_rpc_connector_->CallRpc("write_single_coil", req.ToJSONString(), + nullptr); +} +void Robot::RobotImpl::writeMultipleCoils(const modbus::SetCoilsRequest &req) { + json_rpc_connector_->CallRpc("write_multiple_coils", req.ToJSONString(), + nullptr); +} +modbus::GetCoilsResponse Robot::RobotImpl::readCoils( + const modbus::GetCoilsRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("read_coils", req.ToJSONString(), &resp_str); + modbus::GetCoilsResponse resp; + resp.FromJSONString(resp_str); + return resp; +} +modbus::GetCoilsResponse Robot::RobotImpl::readDiscreteInputs( + const modbus::GetCoilsRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("read_discrete_inputs", req.ToJSONString(), + &resp_str); + modbus::GetCoilsResponse resp; + resp.FromJSONString(resp_str); + return resp; +} +void Robot::RobotImpl::writeSingleRegister( + const modbus::SetRegisterRequest &req) { + json_rpc_connector_->CallRpc("write_single_register", req.ToJSONString(), + nullptr); +} +void Robot::RobotImpl::writeMultipleRegisters( + const modbus::SetRegistersRequest &req) { + json_rpc_connector_->CallRpc("write_multiple_registers", req.ToJSONString(), + nullptr); +} +modbus::GetRegistersResponse Robot::RobotImpl::readInputRegisters( + const modbus::GetRegistersRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("read_input_registers", req.ToJSONString(), + &resp_str); + modbus::GetRegistersResponse resp; + resp.FromJSONString(resp_str); + return resp; +} +modbus::GetRegistersResponse Robot::RobotImpl::readHoldingRegisters( + const modbus::GetRegistersRequest &req) { + std::string resp_str; + json_rpc_connector_->CallRpc("read_holding_registers", req.ToJSONString(), + &resp_str); + modbus::GetRegistersResponse resp; + resp.FromJSONString(resp_str); + return resp; +} + +void Robot::RobotImpl::setSerialBaudRateRequest( + const serial::SetSerialBaudRateRequest &req) { + json_rpc_connector_->CallRpc("set_serial_baud_rate", req.ToJSONString(), + nullptr); +} +void Robot::RobotImpl::setSerialParityRequest( + const serial::SetSerialParityRequest &req) { + json_rpc_connector_->CallRpc("set_serial_parity", req.ToJSONString(), + nullptr); +} + +} // namespace l_master +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/robot_impl.hh b/sdk/src/robot_impl.hh index 8b37876..3110e87 100644 --- a/sdk/src/robot_impl.hh +++ b/sdk/src/robot_impl.hh @@ -1,22 +1,21 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once - #include #include "protos/motion.hh" #include "protos/system.hh" @@ -33,114 +32,116 @@ #include "protos/modbus.hh" #include "protos/serial.hh" -namespace lebai -{ - namespace l_master - { - class Robot::RobotImpl - { - public: - RobotImpl(const::std::string &ip, bool simulator); - virtual ~RobotImpl(); - std::tuple call(const std::string & method, const std::string & params); - bool isNetworkConnected(); - int startSys(); - int stopSys(); - int powerdown(); - int stop(); - int estop(); - int teachMode(); - int endTeachMode(); - int pause(); - int resume(); - void reboot(); - // // int movej(const std::vector & p, double v, double a, double t, double r, bool relative); - motion::MotionIndex moveJoint(const motion::MoveRequest & req); - motion::MotionIndex moveLinear(const motion::MoveRequest & req); - motion::MotionIndex moveCircular(const motion::MovecRequest & req); - motion::MotionIndex towardJoint(const motion::MoveRequest & req); - motion::MotionIndex speedJoint(const motion::SpeedJRequest & req); - motion::MotionIndex speedLinear(const motion::SpeedLRequest & req); - void movePvat(const motion::MovePvatRequest & req); - void waitMove(const motion::MotionIndex & req); - motion::MotionIndex getRunningMotion(); - motion::GetMotionStateResponse getMotionState(const motion::MotionIndex & req); - void stopMove(); - system::RobotState getRobotState(); - system::EstopReason getEstopReason(); - system::PhyData getPhyData(); - kinematic::KinData getKinData(); - io::GetDioPinResponse getDI(const io::GetDioPinRequest & req); - io::GetDioPinsResponse getDIS(const io::GetDioPinsRequest & req); - io::GetDioPinResponse getDO(const io::GetDioPinRequest & req); - io::GetDioPinsResponse getDOS(const io::GetDioPinsRequest & req); - void setDO(const io::SetDoPinRequest & req); - io::GetAioPinResponse getAI(const io::GetAioPinRequest & req); - io::GetAioPinsResponse getAIS(const io::GetAioPinsRequest & req); - io::GetAioPinResponse getAO(const io::GetAioPinRequest & req); - io::GetAioPinsResponse getAOS(const io::GetAioPinsRequest & req); - void setDioMode(const io::SetDioModeRequest & req); - io::GetDiosModeResponse getDiosMode(const io::GetDiosModeRequest & req); - void setAO(const io::SetAoPinRequest & req); - void setClaw(const claw::SetClawRequest & req); - void setLed(const led::LedData & req); - void setVoice(const led::VoiceData & req); - void setFan(const led::FanData & req); - void setSignal(const signal::SetSignalRequest & req); - signal::GetSignalResponse getSignal(const signal::GetSignalRequest & req); - void addSignal(const signal::SetSignalRequest & req); - control::TaskIndex scene(const control::StartTaskRequest & req); - control::TaskIds loadTaskList(); - void pauseTask(const control::PauseRequest & req); - void resumeTask(const control::TaskIndex & req); - void cancelTask(const control::TaskIndex & req); - control::HookResponse execHook(const control::Exec & req); - control::Task loadTask(const control::TaskIndex & req); - control::Task loadTask(); - claw::Claw getClaw(); - posture::CartesianPose getForwardKin(const posture::PoseRequest & req); - posture::JointPose getInverseKin(const posture::GetInverseKinRequest & req); - posture::CartesianPose getPoseTrans(const posture::GetPoseTransRequest & req); - posture::CartesianPose getPoseInverse(const posture::PoseRequest & req); - void saveFile(const file::SaveFileRequest & req); - void renameFile(const file::RenameFileRequest & req); - file::File loadFile(const file::FileIndex & req); - file::LoadFileListResponse loadFileList(const file::LoadFileListRequest & req); - void zip(const file::ZipRequest & req); - void unzip(const file::UnzipRequest & req); - file::LoadZipListResponse loadZipList(const file::LoadZipListRequest & req); - void setPayload(const dynamic::SetPayloadRequest & req); - void setPayload(const dynamic::SetCogRequest & req); - void setPayload(const dynamic::SetMassRequest & req); - dynamic::Payload getPayload(); - void setGravity(const posture::Position & req); - posture::Position getGravity(); - void savePayload(const dynamic::SavePayloadRequest & req); - dynamic::Payload loadPayload(const db::LoadRequest & req); - db::LoadListResponse loadPayloadList(const db::LoadListRequest & req); - void setTcp(const posture::CartesianPose & req); - posture::CartesianPose getTcp(); - void setKinFactor(const kinematic::KinFactor & req); - kinematic::KinFactor getKinFactor(); - posture::CartesianPose loadTcp(const db::LoadRequest & req); - void writeSingleCoil(const modbus::SetCoilRequest & req); - void writeMultipleCoils(const modbus::SetCoilsRequest & req); - modbus::GetCoilsResponse readCoils(const modbus::GetCoilsRequest & req); - modbus::GetCoilsResponse readDiscreteInputs(const modbus::GetCoilsRequest & req); - void writeSingleRegister(const modbus::SetRegisterRequest & req); - void writeMultipleRegisters(const modbus::SetRegistersRequest & req); - modbus::GetRegistersResponse readInputRegisters(const modbus::GetRegistersRequest & req); - modbus::GetRegistersResponse readHoldingRegisters(const modbus::GetRegistersRequest & req); - void setSerialBaudRateRequest(const serial::SetSerialBaudRateRequest & req); - void setSerialParityRequest(const serial::SetSerialParityRequest & req); +namespace lebai { +namespace l_master { +class Robot::RobotImpl { + public: + RobotImpl(const ::std::string &ip, bool simulator); + virtual ~RobotImpl(); + std::tuple call(const std::string &method, + const std::string ¶ms); + bool isNetworkConnected(); + int startSys(); + int stopSys(); + int powerdown(); + int stop(); + int estop(); + int teachMode(); + int endTeachMode(); + int pause(); + int resume(); + void reboot(); + // // int movej(const std::vector & p, double v, double a, double t, + // double r, bool relative); + motion::MotionIndex moveJoint(const motion::MoveRequest &req); + motion::MotionIndex moveLinear(const motion::MoveRequest &req); + motion::MotionIndex moveCircular(const motion::MovecRequest &req); + motion::MotionIndex towardJoint(const motion::MoveRequest &req); + motion::MotionIndex speedJoint(const motion::SpeedJRequest &req); + motion::MotionIndex speedLinear(const motion::SpeedLRequest &req); + void movePvat(const motion::MovePvatRequest &req); + void waitMove(const motion::MotionIndex &req); + motion::MotionIndex getRunningMotion(); + motion::GetMotionStateResponse getMotionState(const motion::MotionIndex &req); + void stopMove(); + system::RobotState getRobotState(); + system::EstopReason getEstopReason(); + system::PhyData getPhyData(); + kinematic::KinData getKinData(); + io::GetDioPinResponse getDI(const io::GetDioPinRequest &req); + io::GetDioPinsResponse getDIS(const io::GetDioPinsRequest &req); + io::GetDioPinResponse getDO(const io::GetDioPinRequest &req); + io::GetDioPinsResponse getDOS(const io::GetDioPinsRequest &req); + void setDO(const io::SetDoPinRequest &req); + io::GetAioPinResponse getAI(const io::GetAioPinRequest &req); + io::GetAioPinsResponse getAIS(const io::GetAioPinsRequest &req); + io::GetAioPinResponse getAO(const io::GetAioPinRequest &req); + io::GetAioPinsResponse getAOS(const io::GetAioPinsRequest &req); + void setDioMode(const io::SetDioModeRequest &req); + io::GetDiosModeResponse getDiosMode(const io::GetDiosModeRequest &req); + void setAO(const io::SetAoPinRequest &req); + void setClaw(const claw::SetClawRequest &req); + void setLed(const led::LedData &req); + void setVoice(const led::VoiceData &req); + void setFan(const led::FanData &req); + void setSignal(const signal::SetSignalRequest &req); + signal::GetSignalResponse getSignal(const signal::GetSignalRequest &req); + void addSignal(const signal::SetSignalRequest &req); + control::TaskIndex scene(const control::StartTaskRequest &req); + control::TaskIds loadTaskList(); + void pauseTask(const control::PauseRequest &req); + void resumeTask(const control::TaskIndex &req); + void cancelTask(const control::TaskIndex &req); + control::HookResponse execHook(const control::Exec &req); + control::Task loadTask(const control::TaskIndex &req); + control::Task loadTask(); + claw::Claw getClaw(); + posture::CartesianPose getForwardKin(const posture::PoseRequest &req); + posture::JointPose getInverseKin(const posture::GetInverseKinRequest &req); + posture::CartesianPose getPoseTrans(const posture::GetPoseTransRequest &req); + posture::CartesianPose getPoseInverse(const posture::PoseRequest &req); + void saveFile(const file::SaveFileRequest &req); + void renameFile(const file::RenameFileRequest &req); + file::File loadFile(const file::FileIndex &req); + file::LoadFileListResponse loadFileList(const file::LoadFileListRequest &req); + void zip(const file::ZipRequest &req); + void unzip(const file::UnzipRequest &req); + file::LoadZipListResponse loadZipList(const file::LoadZipListRequest &req); + void setPayload(const dynamic::SetPayloadRequest &req); + void setPayload(const dynamic::SetCogRequest &req); + void setPayload(const dynamic::SetMassRequest &req); + dynamic::Payload getPayload(); + void setGravity(const posture::Position &req); + posture::Position getGravity(); + void savePayload(const dynamic::SavePayloadRequest &req); + dynamic::Payload loadPayload(const db::LoadRequest &req); + db::LoadListResponse loadPayloadList(const db::LoadListRequest &req); + void setTcp(const posture::CartesianPose &req); + posture::CartesianPose getTcp(); + void setKinFactor(const kinematic::KinFactor &req); + kinematic::KinFactor getKinFactor(); + posture::CartesianPose loadTcp(const db::LoadRequest &req); + void writeSingleCoil(const modbus::SetCoilRequest &req); + void writeMultipleCoils(const modbus::SetCoilsRequest &req); + modbus::GetCoilsResponse readCoils(const modbus::GetCoilsRequest &req); + modbus::GetCoilsResponse readDiscreteInputs( + const modbus::GetCoilsRequest &req); + void writeSingleRegister(const modbus::SetRegisterRequest &req); + void writeMultipleRegisters(const modbus::SetRegistersRequest &req); + modbus::GetRegistersResponse readInputRegisters( + const modbus::GetRegistersRequest &req); + modbus::GetRegistersResponse readHoldingRegisters( + const modbus::GetRegistersRequest &req); + void setSerialBaudRateRequest(const serial::SetSerialBaudRateRequest &req); + void setSerialParityRequest(const serial::SetSerialParityRequest &req); - protected: - std::unique_ptr json_rpc_connector_; - double timeout_ = 1.0; - const uint16_t simulation_port_ = 3030; - const uint16_t physical_machine_port_ = 3031; - // int jsonrpc_id_ = 0; - // WebSocketEndPoint endpoint_; - }; - } // namespace l_master -} \ No newline at end of file + protected: + std::unique_ptr json_rpc_connector_; + double timeout_ = 1.0; + const uint16_t simulation_port_ = 3030; + const uint16_t physical_machine_port_ = 3031; + // int jsonrpc_id_ = 0; + // WebSocketEndPoint endpoint_; +}; +} // namespace l_master +} // namespace lebai \ No newline at end of file diff --git a/sdk/src/websocket.hh b/sdk/src/websocket.hh index 0a24a70..445b2de 100644 --- a/sdk/src/websocket.hh +++ b/sdk/src/websocket.hh @@ -1,18 +1,18 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #pragma once @@ -35,307 +35,269 @@ #include #include "protos/utils.hh" - -namespace lebai -{ - typedef websocketpp::client WSClient; - - class ConnectionMetadata - { - public: - using ptr = websocketpp::lib::shared_ptr; - - ConnectionMetadata(int id, websocketpp::connection_hdl hdl, std::string uri) - : id_(id), - hdl_(hdl), - status_("Connecting"), - uri_(uri), - server_("N/A") {} - - void onOpen(WSClient *c, websocketpp::connection_hdl hdl) - { - std::lock_guard guard(status_mutex_); - status_ = "Open"; - WSClient::connection_ptr con = c->get_con_from_hdl(hdl); - server_ = con->get_response_header("Server"); - } - - void onFail(WSClient *c, websocketpp::connection_hdl hdl) - { - std::lock_guard guard(status_mutex_); - status_ = "Failed"; - WSClient::connection_ptr con = c->get_con_from_hdl(hdl); - server_ = con->get_response_header("Server"); - error_reason_ = con->get_ec().message(); - } - - void onClose(WSClient *c, websocketpp::connection_hdl hdl) - { - std::lock_guard guard(status_mutex_); - status_ = "Closed"; - WSClient::connection_ptr con = c->get_con_from_hdl(hdl); - std::stringstream s; - s << "close code: " << con->get_remote_close_code() << " (" - << websocketpp::close::status::get_string(con->get_remote_close_code()) - << "), close reason: " << con->get_remote_close_reason(); - error_reason_ = s.str(); - } - - void onMessage(websocketpp::connection_hdl, WSClient::message_ptr msg) - { - std::lock_guard guard(promises_map_mutex_); - std::string message_str = msg->get_payload(); - int callback_jsonrpc_id; - int error_code; - std::string resp_data_str; - auto ret = ExtractJSONRpcRespString(message_str, callback_jsonrpc_id, error_code, resp_data_str); - if(ret == JSONRpcRespParseResult::kInvalid) - { - std::cout<<"invalid jsonrpc response\n"; - return; - } - else - { - if(promises_.find(callback_jsonrpc_id) != promises_.end()) - { - if(ret == JSONRpcRespParseResult::kResult) - { - promises_[callback_jsonrpc_id]->set_value(std::make_tuple(0, resp_data_str)); - promises_.erase(callback_jsonrpc_id); - } - else - { - promises_[callback_jsonrpc_id]->set_value(std::make_tuple(error_code, resp_data_str)); - promises_.erase(callback_jsonrpc_id); - } - } - else{ - // Should not happen +namespace lebai { +typedef websocketpp::client WSClient; + +class ConnectionMetadata { + public: + using ptr = websocketpp::lib::shared_ptr; + + ConnectionMetadata(int id, websocketpp::connection_hdl hdl, std::string uri) + : id_(id), hdl_(hdl), status_("Connecting"), uri_(uri), server_("N/A") {} + + void onOpen(WSClient *c, websocketpp::connection_hdl hdl) { + std::lock_guard guard(status_mutex_); + status_ = "Open"; + WSClient::connection_ptr con = c->get_con_from_hdl(hdl); + server_ = con->get_response_header("Server"); + } + + void onFail(WSClient *c, websocketpp::connection_hdl hdl) { + std::lock_guard guard(status_mutex_); + status_ = "Failed"; + WSClient::connection_ptr con = c->get_con_from_hdl(hdl); + server_ = con->get_response_header("Server"); + error_reason_ = con->get_ec().message(); + } + + void onClose(WSClient *c, websocketpp::connection_hdl hdl) { + std::lock_guard guard(status_mutex_); + status_ = "Closed"; + WSClient::connection_ptr con = c->get_con_from_hdl(hdl); + std::stringstream s; + s << "close code: " << con->get_remote_close_code() << " (" + << websocketpp::close::status::get_string(con->get_remote_close_code()) + << "), close reason: " << con->get_remote_close_reason(); + error_reason_ = s.str(); + } + + void onMessage(websocketpp::connection_hdl, WSClient::message_ptr msg) { + std::lock_guard guard(promises_map_mutex_); + std::string message_str = msg->get_payload(); + int callback_jsonrpc_id; + int error_code; + std::string resp_data_str; + auto ret = ExtractJSONRpcRespString(message_str, callback_jsonrpc_id, + error_code, resp_data_str); + if (ret == JSONRpcRespParseResult::kInvalid) { + std::cout << "invalid jsonrpc response\n"; + return; + } else { + if (promises_.find(callback_jsonrpc_id) != promises_.end()) { + if (ret == JSONRpcRespParseResult::kResult) { + promises_[callback_jsonrpc_id]->set_value( + std::make_tuple(0, resp_data_str)); + promises_.erase(callback_jsonrpc_id); + } else { + promises_[callback_jsonrpc_id]->set_value( + std::make_tuple(error_code, resp_data_str)); + promises_.erase(callback_jsonrpc_id); } + } else { + // Should not happen } } + } - websocketpp::connection_hdl getHDL() const { return hdl_; } - - int getID() const { return id_; } + websocketpp::connection_hdl getHDL() const { return hdl_; } - std::string getStatus() { - std::lock_guard guard(status_mutex_); - return status_; - } + int getID() const { return id_; } - // void record_sent_message(std::string message) { - // m_messages.push_back(">> " + message); - // } + std::string getStatus() { + std::lock_guard guard(status_mutex_); + return status_; + } - std::future> createPromise(int rpc_id) - { - std::lock_guard guard(promises_map_mutex_); - promises_[rpc_id] = std::make_unique>>(); - return promises_[rpc_id]->get_future();; - } - void deletePromise(int rpc_id) - { - std::lock_guard guard(promises_map_mutex_); - if(promises_.find(rpc_id) != promises_.end()) - { - promises_.erase(rpc_id); - } - } - - - // friend std::ostream& operator<<(std::ostream& out, - // ConnectionMetadata const& data); - - private: - std::map>>> promises_; - int id_; - websocketpp::connection_hdl hdl_; - std::string status_; - std::string uri_; - std::string server_; - std::string error_reason_; - std::mutex promises_map_mutex_; - std::mutex status_mutex_; - }; - - // std::ostream& operator<<(std::ostream& out, ConnectionMetadata const& data) { - // out << "> URI: " << data.m_uri << "\n" - // << "> Status: " << data.m_status << "\n" - // << "> Remote Server: " - // << (data.m_server.empty() ? "None Specified" : data.m_server) << "\n" - // << "> Error/close reason: " - // << (data.m_error_reason.empty() ? "N/A" : data.m_error_reason) << "\n"; - // out << "> Messages Processed: (" << data.m_messages.size() << ") \n"; - - // std::vector::const_iterator it; - // for (it = data.m_messages.begin(); it != data.m_messages.end(); ++it) { - // out << *it << "\n"; - // } - - // return out; + // void record_sent_message(std::string message) { + // m_messages.push_back(">> " + message); // } - class WebSocketEndPoint - { - public: - WebSocketEndPoint() : next_id_(0) - { - endpoint_.clear_access_channels(websocketpp::log::alevel::all); - endpoint_.clear_error_channels(websocketpp::log::elevel::all); - - endpoint_.init_asio(); - endpoint_.start_perpetual(); - - thread_ = websocketpp::lib::make_shared( - &WSClient::run, &endpoint_); + std::future> createPromise(int rpc_id) { + std::lock_guard guard(promises_map_mutex_); + promises_[rpc_id] = + std::make_unique>>(); + return promises_[rpc_id]->get_future(); + ; + } + void deletePromise(int rpc_id) { + std::lock_guard guard(promises_map_mutex_); + if (promises_.find(rpc_id) != promises_.end()) { + promises_.erase(rpc_id); } - - ~WebSocketEndPoint() - { - endpoint_.stop_perpetual(); - - for (ConList::const_iterator it = connection_list_.begin(); - it != connection_list_.end(); ++it) - { - if (it->second->getStatus() != "Open") - { - // Only close open connections - continue; - } - - websocketpp::lib::error_code ec; - endpoint_.close(it->second->getHDL(), - websocketpp::close::status::going_away, "", ec); - if (ec) - { - std::cout << "> Error closing connection " << it->second->getID() - << ": " << ec.message() << std::endl; - } + } + + // friend std::ostream& operator<<(std::ostream& out, + // ConnectionMetadata const& data); + + private: + std::map>>> + promises_; + int id_; + websocketpp::connection_hdl hdl_; + std::string status_; + std::string uri_; + std::string server_; + std::string error_reason_; + std::mutex promises_map_mutex_; + std::mutex status_mutex_; +}; + +// std::ostream& operator<<(std::ostream& out, ConnectionMetadata const& data) { +// out << "> URI: " << data.m_uri << "\n" +// << "> Status: " << data.m_status << "\n" +// << "> Remote Server: " +// << (data.m_server.empty() ? "None Specified" : data.m_server) << "\n" +// << "> Error/close reason: " +// << (data.m_error_reason.empty() ? "N/A" : data.m_error_reason) << "\n"; +// out << "> Messages Processed: (" << data.m_messages.size() << ") \n"; + +// std::vector::const_iterator it; +// for (it = data.m_messages.begin(); it != data.m_messages.end(); ++it) { +// out << *it << "\n"; +// } + +// return out; +// } + +class WebSocketEndPoint { + public: + WebSocketEndPoint() : next_id_(0) { + endpoint_.clear_access_channels(websocketpp::log::alevel::all); + endpoint_.clear_error_channels(websocketpp::log::elevel::all); + + endpoint_.init_asio(); + endpoint_.start_perpetual(); + + thread_ = websocketpp::lib::make_shared( + &WSClient::run, &endpoint_); + } + + ~WebSocketEndPoint() { + endpoint_.stop_perpetual(); + + for (ConList::const_iterator it = connection_list_.begin(); + it != connection_list_.end(); ++it) { + if (it->second->getStatus() != "Open") { + // Only close open connections + continue; } - thread_->join(); - } - int connect(std::string const &uri) - { websocketpp::lib::error_code ec; - - WSClient::connection_ptr con = endpoint_.get_connection(uri, ec); - - if (ec) - { - std::cout << "> Connect initialization error: " << ec.message() - << std::endl; - return -1; + endpoint_.close(it->second->getHDL(), + websocketpp::close::status::going_away, "", ec); + if (ec) { + std::cout << "> Error closing connection " << it->second->getID() + << ": " << ec.message() << std::endl; } - - int new_id = next_id_++; - ConnectionMetadata::ptr metadata_ptr = - websocketpp::lib::make_shared( - new_id, con->get_handle(), uri); - connection_list_[new_id] = metadata_ptr; - - con->set_open_handler(websocketpp::lib::bind( - &ConnectionMetadata::onOpen, metadata_ptr, &endpoint_, - websocketpp::lib::placeholders::_1)); - con->set_fail_handler(websocketpp::lib::bind( - &ConnectionMetadata::onFail, metadata_ptr, &endpoint_, - websocketpp::lib::placeholders::_1)); - con->set_close_handler(websocketpp::lib::bind( - &ConnectionMetadata::onClose, metadata_ptr, &endpoint_, - websocketpp::lib::placeholders::_1)); - con->set_message_handler( - websocketpp::lib::bind(&ConnectionMetadata::onMessage, metadata_ptr, - websocketpp::lib::placeholders::_1, - websocketpp::lib::placeholders::_2)); - - endpoint_.connect(con); - return new_id; } + thread_->join(); + } - void close(int id, websocketpp::close::status::value code, - std::string reason) - { - websocketpp::lib::error_code ec; + int connect(std::string const &uri) { + websocketpp::lib::error_code ec; - ConList::iterator metadata_it = connection_list_.find(id); - if (metadata_it == connection_list_.end()) - { - std::cout << "> No connection found with id " << id << std::endl; - return; - } + WSClient::connection_ptr con = endpoint_.get_connection(uri, ec); - endpoint_.close(metadata_it->second->getHDL(), code, reason, ec); - if (ec) - { - std::cout << "> Error initiating close: " << ec.message() << std::endl; - } + if (ec) { + std::cout << "> Connect initialization error: " << ec.message() + << std::endl; + return -1; } - bool send(int id, std::string message) - { - websocketpp::lib::error_code ec; - - ConList::iterator metadata_it = connection_list_.find(id); - if (metadata_it == connection_list_.end()) - { - // std::cout << "> No connection found with id " << id << std::endl; - return false; - } - - endpoint_.send(metadata_it->second->getHDL(), message, - websocketpp::frame::opcode::text, ec); - - if (ec) - { - std::cout << "> Error sending message: " << ec.message() << std::endl; - return false; - } - return true; - - // std::unique_lock lock(mutex); - // cv.wait(lock, [] { return processed; }); - // metadata_it->second->record_sent_message(message); + int new_id = next_id_++; + ConnectionMetadata::ptr metadata_ptr = + websocketpp::lib::make_shared( + new_id, con->get_handle(), uri); + connection_list_[new_id] = metadata_ptr; + + con->set_open_handler( + websocketpp::lib::bind(&ConnectionMetadata::onOpen, metadata_ptr, + &endpoint_, websocketpp::lib::placeholders::_1)); + con->set_fail_handler( + websocketpp::lib::bind(&ConnectionMetadata::onFail, metadata_ptr, + &endpoint_, websocketpp::lib::placeholders::_1)); + con->set_close_handler( + websocketpp::lib::bind(&ConnectionMetadata::onClose, metadata_ptr, + &endpoint_, websocketpp::lib::placeholders::_1)); + con->set_message_handler( + websocketpp::lib::bind(&ConnectionMetadata::onMessage, metadata_ptr, + websocketpp::lib::placeholders::_1, + websocketpp::lib::placeholders::_2)); + + endpoint_.connect(con); + return new_id; + } + + void close(int id, websocketpp::close::status::value code, + std::string reason) { + websocketpp::lib::error_code ec; + + ConList::iterator metadata_it = connection_list_.find(id); + if (metadata_it == connection_list_.end()) { + std::cout << "> No connection found with id " << id << std::endl; + return; } - std::future> createFuture(int id, int rpc_id) - { - // metadata_it->second->SetReqFlag(true); - // metadata_it->second->notify(); - // metadata_it->second->waitCV(); - // metadata_it->second->SetReqFlag(false); - // metadata_it->second->SetRespFlag(false); - ConList::iterator metadata_it = connection_list_.find(id); - return metadata_it->second->createPromise(rpc_id); + + endpoint_.close(metadata_it->second->getHDL(), code, reason, ec); + if (ec) { + std::cout << "> Error initiating close: " << ec.message() << std::endl; } + } - void deletePromise(int id, int rpc_id) - { - ConList::iterator metadata_it = connection_list_.find(id); - metadata_it->second->deletePromise(rpc_id); + bool send(int id, std::string message) { + websocketpp::lib::error_code ec; + + ConList::iterator metadata_it = connection_list_.find(id); + if (metadata_it == connection_list_.end()) { + // std::cout << "> No connection found with id " << id << std::endl; + return false; } + endpoint_.send(metadata_it->second->getHDL(), message, + websocketpp::frame::opcode::text, ec); - ConnectionMetadata::ptr get_metadata(int id) const - { - ConList::const_iterator metadata_it = connection_list_.find(id); - if (metadata_it == connection_list_.end()) - { - return ConnectionMetadata::ptr(); - } - else - { - return metadata_it->second; - } + if (ec) { + std::cout << "> Error sending message: " << ec.message() << std::endl; + return false; + } + return true; + + // std::unique_lock lock(mutex); + // cv.wait(lock, [] { return processed; }); + // metadata_it->second->record_sent_message(message); + } + std::future> createFuture(int id, int rpc_id) { + // metadata_it->second->SetReqFlag(true); + // metadata_it->second->notify(); + // metadata_it->second->waitCV(); + // metadata_it->second->SetReqFlag(false); + // metadata_it->second->SetRespFlag(false); + ConList::iterator metadata_it = connection_list_.find(id); + return metadata_it->second->createPromise(rpc_id); + } + + void deletePromise(int id, int rpc_id) { + ConList::iterator metadata_it = connection_list_.find(id); + metadata_it->second->deletePromise(rpc_id); + } + + ConnectionMetadata::ptr get_metadata(int id) const { + ConList::const_iterator metadata_it = connection_list_.find(id); + if (metadata_it == connection_list_.end()) { + return ConnectionMetadata::ptr(); + } else { + return metadata_it->second; } + } - private: - typedef std::map ConList; + private: + typedef std::map ConList; - WSClient endpoint_; - websocketpp::lib::shared_ptr thread_; + WSClient endpoint_; + websocketpp::lib::shared_ptr thread_; - ConList connection_list_; - int next_id_; - }; + ConList connection_list_; + int next_id_; +}; -} \ No newline at end of file +} // namespace lebai \ No newline at end of file diff --git a/sdk/test/test_discovery.cc b/sdk/test/test_discovery.cc index 6bd44d0..75dd2e2 100644 --- a/sdk/test/test_discovery.cc +++ b/sdk/test/test_discovery.cc @@ -1,51 +1,43 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #include #include #include #include -namespace lebai -{ - class DiscoveryTest : public ::testing::Test - { - public: - DiscoveryTest() - { - } - void SetUp() - { - } +namespace lebai { +class DiscoveryTest : public ::testing::Test { + public: + DiscoveryTest() {} + void SetUp() {} - protected: - }; - TEST_F(DiscoveryTest, Basic) - { - lebai::zeroconf::Discovery discovery; - auto controller_data = discovery.resolve(); - // for (auto& data : controller_data) - // { - // std::cout << "ip: " << data.ip_address << std::endl; - // } - } + protected: +}; +TEST_F(DiscoveryTest, Basic) { + lebai::zeroconf::Discovery discovery; + auto controller_data = discovery.resolve(); + // for (auto& data : controller_data) + // { + // std::cout << "ip: " << data.ip_address << std::endl; + // } } +} // namespace lebai -int main(int argc, char **argv) -{ +int main(int argc, char **argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/sdk/test/test_lua_robot.cc b/sdk/test/test_lua_robot.cc index 3e093af..e98a2ac 100644 --- a/sdk/test/test_lua_robot.cc +++ b/sdk/test/test_lua_robot.cc @@ -1,72 +1,73 @@ /** * Copyright 2022-2023 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #include #include #include #include #include "lebai/lua_robot.hh" -namespace lebai -{ - class LuaRobotTest : public ::testing::Test - { - public: - LuaRobotTest() - :lua_robot_(TEST_L_MASTER_IP) - { - // std::cout<<"TEST_L_MASTER_IP "< codes; - codes.push_back("start_sys()"); - codes.push_back("movej({j1 = 1.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = 0}, 1.2, 0.2, 0, 0)"); - codes.push_back("movej({j1 = 0.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = 0}, 1.2, 0.2, 0, 0)"); - codes.push_back("sync()"); - codes.push_back("stop_sys()"); - EXPECT_NO_THROW(lua_robot_.send(codes)); +namespace lebai { +class LuaRobotTest : public ::testing::Test { + public: + LuaRobotTest() : lua_robot_(TEST_L_MASTER_IP) { + // std::cout<<"TEST_L_MASTER_IP "< codes; + codes.push_back("start_sys()"); + codes.push_back( + "movej({j1 = 1.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = 0}, 1.2, 0.2, 0, " + "0)"); + codes.push_back( + "movej({j1 = 0.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = 0}, 1.2, 0.2, 0, " + "0)"); + codes.push_back("sync()"); + codes.push_back("stop_sys()"); + EXPECT_NO_THROW(lua_robot_.send(codes)); +} +TEST_F(LuaRobotTest, CallCase) { + EXPECT_NO_THROW(lua_robot_.send("start_sys()")); + EXPECT_NO_THROW( + lua_robot_.send("movej({j1 = 0.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = " + "0}, 1.2, 0.2, 0, 0)")); + EXPECT_NO_THROW( + lua_robot_.send("movej({j1 = 1.0, j2 = 0, j3 = 0, j4 = 0, j5 = 0, j6 = " + "0}, 1.2, 0.2, 0, 0)")); - } + std::string jps; + EXPECT_NO_THROW(jps = lua_robot_.call("get_target_joint_positions()")); + EXPECT_TRUE(jps.size()); } +} // namespace lebai -int main(int argc, char **argv) -{ +int main(int argc, char **argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/sdk/test/test_protos.cc b/sdk/test/test_protos.cc index ebcd502..ce6b0b3 100644 --- a/sdk/test/test_protos.cc +++ b/sdk/test/test_protos.cc @@ -1,296 +1,387 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #include #include #include #include "protos/posture.hh" #include "protos/motion.hh" -namespace lebai -{ - class ProtosTest : public ::testing::Test - { - public: - ProtosTest() - { - } - void SetUp() - { - } +namespace lebai { +class ProtosTest : public ::testing::Test { + public: + ProtosTest() {} + void SetUp() {} - protected: - }; - TEST_F(ProtosTest, TestPosture) + protected: +}; +TEST_F(ProtosTest, TestPosture) { { - { - lebai::posture::JointPose joint_pose; - joint_pose.set_joint({0.1,0.2}); - ASSERT_EQ(2, joint_pose.joint().size()); - EXPECT_NEAR(0.1, joint_pose.joint()[0], 1e-6); - EXPECT_NEAR(0.2, joint_pose.joint()[1], 1e-6); - auto joint_pose_json_str = joint_pose.ToJSONString(); - lebai::posture::JointPose joint_pose_check; - joint_pose_check.FromJSONString(joint_pose_json_str); - ASSERT_EQ(2, joint_pose_check.joint().size()); - EXPECT_NEAR(0.1, joint_pose_check.joint()[0], 1e-6); - EXPECT_NEAR(0.2, joint_pose_check.joint()[1], 1e-6); - } - { - lebai::posture::Position position, position_check; - position.set_x(0.1); - position.set_y(0.2); - position.set_z(0.3); - auto json_str = position.ToJSONString(); - position_check.FromJSONString(json_str); - EXPECT_NEAR(0.1, position_check.x(), 1e-6); - EXPECT_NEAR(0.2, *position_check.mutable_y(), 1e-6); - EXPECT_NEAR(0.3, position_check.z(), 1e-6); - } - { - lebai::posture::RotationMatrix m, m_check; - EXPECT_NEAR(1, m_check.data()[0], 1e-6); - EXPECT_NEAR(1, m_check.data()[4], 1e-6); - EXPECT_NEAR(1, m_check.data()[8], 1e-6); - m.set_data({{1,2,3,4,5,6,7,8,9}}); - auto json_str = m.ToJSONString(); - m_check.FromJSONString(json_str); - EXPECT_NEAR(1, m_check.data()[0], 1e-6); - EXPECT_NEAR(2, (*m_check.mutable_data())[1], 1e-6); - EXPECT_NEAR(5, (*m_check.mutable_data())[4], 1e-6); - EXPECT_NEAR(9, m_check.data()[8], 1e-6); - } - { - lebai::posture::Rotation r, r_check; - EXPECT_TRUE(r.mutable_rotation_matrix()); - auto json_str = r.ToJSONString(); - r_check.FromJSONString(json_str); - EXPECT_TRUE(r_check.mutable_rotation_matrix()); - EXPECT_NEAR(1, r_check.rotation_matrix()->data()[4], 1e-6); - lebai::posture::Quaternion quat; - r.set_quaternion(quat); - EXPECT_TRUE(r.mutable_quaternion()); - json_str = r.ToJSONString(); - r_check.FromJSONString(json_str); - EXPECT_TRUE(r_check.mutable_rotation_matrix()); - lebai::posture::Position euler_zyx; - r.set_euler_zyx(euler_zyx); - EXPECT_TRUE(r.mutable_euler_zyx()); - json_str = r.ToJSONString(); - r_check.FromJSONString(json_str); - EXPECT_TRUE(r_check.mutable_euler_zyx()); - } - { - lebai::posture::CartesianFrame cf, cf_check; - cf.set_position_kind(lebai::posture::CartesianFrame::Kind::FLANGE); - cf.mutable_position()->set_x(0.1); - cf.mutable_position()->set_y(0.2); - cf.mutable_position()->set_z(0.3); - cf.set_rotation_kind(lebai::posture::CartesianFrame::Kind::TCP); - cf.mutable_rotation()->mutable_euler_zyx()->set_x(0.4); - cf.mutable_rotation()->mutable_euler_zyx()->set_y(0.5); - cf.mutable_rotation()->mutable_euler_zyx()->set_z(0.6); - auto json_str = cf.ToJSONString(); - // std::cout<<"json_str:"<x(), 1e-6); - EXPECT_NEAR(0.2, cf_check.mutable_position()->y(), 1e-6); - EXPECT_NEAR(0.3, cf_check.mutable_position()->z(), 1e-6); - EXPECT_EQ(1, cf_check.position_kind()); - EXPECT_EQ(2, cf_check.rotation_kind()); - EXPECT_NEAR(0.4, cf_check.rotation().euler_zyx()->x(), 1e-6); - EXPECT_NEAR(0.5, cf_check.rotation().euler_zyx()->y(), 1e-6); - EXPECT_NEAR(0.6, cf_check.rotation().euler_zyx()->z(), 1e-6); - } - { - lebai::posture::CartesianPose cp, cp_check; - cp.mutable_position()->set_x(0.1); - cp.mutable_position()->set_y(0.2); - cp.mutable_position()->set_z(0.3); - cp.mutable_rotation()->mutable_euler_zyx()->set_x(0.4); - cp.mutable_rotation()->mutable_euler_zyx()->set_y(0.5); - cp.mutable_rotation()->mutable_euler_zyx()->set_z(0.6); - auto json_str = cp.ToJSONString(); - // std::cout<<"json_str:"<x(), 1e-6); - EXPECT_NEAR(0.2, cp_check.mutable_position()->y(), 1e-6); - EXPECT_NEAR(0.3, cp_check.mutable_position()->z(), 1e-6); - EXPECT_NEAR(0.4, cp_check.rotation().euler_zyx()->x(), 1e-6); - EXPECT_NEAR(0.5, cp_check.rotation().euler_zyx()->y(), 1e-6); - EXPECT_NEAR(0.6, cp_check.rotation().euler_zyx()->z(), 1e-6); - } - // { - // lebai::posture::CartesianTargetPose ctp, ctp_check; - // ctp.mutable_base()->mutable_position()->set_x(0.1); - // ctp.mutable_base()->mutable_position()->set_y(0.2); - // ctp.mutable_base()->mutable_position()->set_z(0.3); - // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->set_x(0.4); - // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->set_y(0.5); - // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->set_z(0.6); - // auto json_str = ctp.ToJSONString(); - // // std::cout<<"json_str:"<mutable_position()->x(), 1e-6); - // EXPECT_NEAR(0.2, ctp_check.mutable_base()->mutable_position()->y(), 1e-6); - // EXPECT_NEAR(0.3, ctp_check.mutable_base()->mutable_position()->z(), 1e-6); - // EXPECT_NEAR(0.4, ctp_check.mutable_base()->mutable_rotation()->mutable_euler_zyx()->x(), 1e-6); - // EXPECT_NEAR(0.5, ctp_check.mutable_base()->mutable_rotation()->mutable_euler_zyx()->y(), 1e-6); - // EXPECT_NEAR(0.6, ctp_check.mutable_base()->mutable_rotation()->mutable_euler_zyx()->z(), 1e-6); - // } - { - lebai::posture::Pose pose, pose_check; - pose.mutable_joint()->set_joint({1.0,2.0,3.0,4.0,5.0,6.0}); - auto json_str = pose.ToJSONString(); - pose_check.FromJSONString(json_str); - json_str = pose_check.ToJSONString(); - // ASSERT_FALSE(pose_check.mutable_cart()); - ASSERT_EQ(6, pose_check.mutable_joint()->joint().size()); - EXPECT_NEAR(6.0, pose_check.mutable_joint()->joint()[5], 1e-6); - pose.mutable_cart()->mutable_position()->set_x(0.1); - pose.mutable_cart()->mutable_position()->set_y(0.2); - pose.mutable_cart()->mutable_position()->set_z(0.3); - json_str = pose.ToJSONString(); - pose_check.FromJSONString(json_str); - // ASSERT_FALSE(pose_check.joint()); - EXPECT_NEAR(0.1, pose_check.mutable_cart()->position().x(), 1e-6); - EXPECT_NEAR(0.2, pose_check.mutable_cart()->position().y(), 1e-6); - EXPECT_NEAR(0.3, pose_check.mutable_cart()->position().z(), 1e-6); - - - // EXPECT_NEAR(0.2, ctp_check.mutable_base()->mutable_position()->y(), 1e-6); - // EXPECT_NEAR(0.3, ctp_check.mutable_base()->mutable_position()->z(), 1e-6); - // EXPECT_NEAR(0.4, ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->x(), 1e-6); - // EXPECT_NEAR(0.5, ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->y(), 1e-6); - // EXPECT_NEAR(0.6, ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->z(), 1e-6); - } - { - lebai::posture::Rotation rot, rot_check; - rot.mutable_euler_zyx()->set_x(0.1); - rot.mutable_euler_zyx()->set_y(0.2); - rot.mutable_euler_zyx()->set_z(0.3); - auto json_str = rot.ToJSONString(); - rot_check.FromJSONString(json_str); - EXPECT_NEAR(0.1, rot_check.euler_zyx()->x(), 1e-6); - EXPECT_NEAR(0.2, rot_check.euler_zyx()->y(), 1e-6); - EXPECT_NEAR(0.3, rot_check.euler_zyx()->z(), 1e-6); - // std::cout<<"json_str:"<mutable_cart()->mutable_position()->set_x(0.1); - req.mutable_from()->mutable_cart()->mutable_position()->set_y(0.2); - req.mutable_from()->mutable_cart()->mutable_position()->set_z(0.3); - req.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(0.4); - req.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(0.5); - req.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(0.6); - - req.mutable_from_to()->mutable_cart()->mutable_position()->set_x(0.1); - req.mutable_from_to()->mutable_cart()->mutable_position()->set_y(0.2); - req.mutable_from_to()->mutable_cart()->mutable_position()->set_z(0.3); - req.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_x(0.4); - req.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_y(0.5); - req.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->set_z(0.6); - auto json_str = req.ToJSONString(); - req_check.FromJSONString(json_str); - EXPECT_NEAR(0.1, req_check.mutable_from()->mutable_cart()->mutable_position()->x(), 1e-6); - EXPECT_NEAR(0.2, req_check.mutable_from()->mutable_cart()->mutable_position()->y(), 1e-6); - EXPECT_NEAR(0.3, req_check.mutable_from()->mutable_cart()->mutable_position()->z(), 1e-6); - EXPECT_NEAR(0.4, req_check.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->x(), 1e-6); - EXPECT_NEAR(0.5, req_check.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->y(), 1e-6); - EXPECT_NEAR(0.6, req_check.mutable_from()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->z(), 1e-6); - - EXPECT_NEAR(0.1, req_check.mutable_from_to()->mutable_cart()->mutable_position()->x(), 1e-6); - EXPECT_NEAR(0.2, req_check.mutable_from_to()->mutable_cart()->mutable_position()->y(), 1e-6); - EXPECT_NEAR(0.3, req_check.mutable_from_to()->mutable_cart()->mutable_position()->z(), 1e-6); - EXPECT_NEAR(0.4, req_check.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->x(), 1e-6); - EXPECT_NEAR(0.5, req_check.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->y(), 1e-6); - EXPECT_NEAR(0.6, req_check.mutable_from_to()->mutable_cart()->mutable_rotation()->mutable_euler_zyx()->z(), 1e-6); - } - { - lebai::motion::SpeedParam data, data_check; - *data.mutable_acc() = 0.1; - *data.mutable_time() = 0.2; - *data.mutable_constrained() = true; - auto json_str = data.ToJSONString(); - data_check.FromJSONString(json_str); - EXPECT_NEAR(0.1, *data_check.acc(), 1e-6); - EXPECT_NEAR(0.2, *data_check.time(), 1e-6); - EXPECT_TRUE(*data_check.constrained()); + lebai::posture::JointPose joint_pose; + joint_pose.set_joint({0.1, 0.2}); + ASSERT_EQ(2, joint_pose.joint().size()); + EXPECT_NEAR(0.1, joint_pose.joint()[0], 1e-6); + EXPECT_NEAR(0.2, joint_pose.joint()[1], 1e-6); + auto joint_pose_json_str = joint_pose.ToJSONString(); + lebai::posture::JointPose joint_pose_check; + joint_pose_check.FromJSONString(joint_pose_json_str); + ASSERT_EQ(2, joint_pose_check.joint().size()); + EXPECT_NEAR(0.1, joint_pose_check.joint()[0], 1e-6); + EXPECT_NEAR(0.2, joint_pose_check.joint()[1], 1e-6); + } + { + lebai::posture::Position position, position_check; + position.set_x(0.1); + position.set_y(0.2); + position.set_z(0.3); + auto json_str = position.ToJSONString(); + position_check.FromJSONString(json_str); + EXPECT_NEAR(0.1, position_check.x(), 1e-6); + EXPECT_NEAR(0.2, *position_check.mutable_y(), 1e-6); + EXPECT_NEAR(0.3, position_check.z(), 1e-6); + } + { + lebai::posture::RotationMatrix m, m_check; + EXPECT_NEAR(1, m_check.data()[0], 1e-6); + EXPECT_NEAR(1, m_check.data()[4], 1e-6); + EXPECT_NEAR(1, m_check.data()[8], 1e-6); + m.set_data({{1, 2, 3, 4, 5, 6, 7, 8, 9}}); + auto json_str = m.ToJSONString(); + m_check.FromJSONString(json_str); + EXPECT_NEAR(1, m_check.data()[0], 1e-6); + EXPECT_NEAR(2, (*m_check.mutable_data())[1], 1e-6); + EXPECT_NEAR(5, (*m_check.mutable_data())[4], 1e-6); + EXPECT_NEAR(9, m_check.data()[8], 1e-6); + } + { + lebai::posture::Rotation r, r_check; + EXPECT_TRUE(r.mutable_rotation_matrix()); + auto json_str = r.ToJSONString(); + r_check.FromJSONString(json_str); + EXPECT_TRUE(r_check.mutable_rotation_matrix()); + EXPECT_NEAR(1, r_check.rotation_matrix()->data()[4], 1e-6); + lebai::posture::Quaternion quat; + r.set_quaternion(quat); + EXPECT_TRUE(r.mutable_quaternion()); + json_str = r.ToJSONString(); + r_check.FromJSONString(json_str); + EXPECT_TRUE(r_check.mutable_rotation_matrix()); + lebai::posture::Position euler_zyx; + r.set_euler_zyx(euler_zyx); + EXPECT_TRUE(r.mutable_euler_zyx()); + json_str = r.ToJSONString(); + r_check.FromJSONString(json_str); + EXPECT_TRUE(r_check.mutable_euler_zyx()); + } + { + lebai::posture::CartesianFrame cf, cf_check; + cf.set_position_kind(lebai::posture::CartesianFrame::Kind::FLANGE); + cf.mutable_position()->set_x(0.1); + cf.mutable_position()->set_y(0.2); + cf.mutable_position()->set_z(0.3); + cf.set_rotation_kind(lebai::posture::CartesianFrame::Kind::TCP); + cf.mutable_rotation()->mutable_euler_zyx()->set_x(0.4); + cf.mutable_rotation()->mutable_euler_zyx()->set_y(0.5); + cf.mutable_rotation()->mutable_euler_zyx()->set_z(0.6); + auto json_str = cf.ToJSONString(); + // std::cout<<"json_str:"<x(), 1e-6); + EXPECT_NEAR(0.2, cf_check.mutable_position()->y(), 1e-6); + EXPECT_NEAR(0.3, cf_check.mutable_position()->z(), 1e-6); + EXPECT_EQ(1, cf_check.position_kind()); + EXPECT_EQ(2, cf_check.rotation_kind()); + EXPECT_NEAR(0.4, cf_check.rotation().euler_zyx()->x(), 1e-6); + EXPECT_NEAR(0.5, cf_check.rotation().euler_zyx()->y(), 1e-6); + EXPECT_NEAR(0.6, cf_check.rotation().euler_zyx()->z(), 1e-6); + } + { + lebai::posture::CartesianPose cp, cp_check; + cp.mutable_position()->set_x(0.1); + cp.mutable_position()->set_y(0.2); + cp.mutable_position()->set_z(0.3); + cp.mutable_rotation()->mutable_euler_zyx()->set_x(0.4); + cp.mutable_rotation()->mutable_euler_zyx()->set_y(0.5); + cp.mutable_rotation()->mutable_euler_zyx()->set_z(0.6); + auto json_str = cp.ToJSONString(); + // std::cout<<"json_str:"<x(), 1e-6); + EXPECT_NEAR(0.2, cp_check.mutable_position()->y(), 1e-6); + EXPECT_NEAR(0.3, cp_check.mutable_position()->z(), 1e-6); + EXPECT_NEAR(0.4, cp_check.rotation().euler_zyx()->x(), 1e-6); + EXPECT_NEAR(0.5, cp_check.rotation().euler_zyx()->y(), 1e-6); + EXPECT_NEAR(0.6, cp_check.rotation().euler_zyx()->z(), 1e-6); + } + // { + // lebai::posture::CartesianTargetPose ctp, ctp_check; + // ctp.mutable_base()->mutable_position()->set_x(0.1); + // ctp.mutable_base()->mutable_position()->set_y(0.2); + // ctp.mutable_base()->mutable_position()->set_z(0.3); + // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->set_x(0.4); + // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->set_y(0.5); + // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->set_z(0.6); + // auto json_str = ctp.ToJSONString(); + // // std::cout<<"json_str:"<mutable_position()->x(), + // 1e-6); EXPECT_NEAR(0.2, + // ctp_check.mutable_base()->mutable_position()->y(), 1e-6); + // EXPECT_NEAR(0.3, ctp_check.mutable_base()->mutable_position()->z(), + // 1e-6); EXPECT_NEAR(0.4, + // ctp_check.mutable_base()->mutable_rotation()->mutable_euler_zyx()->x(), + // 1e-6); EXPECT_NEAR(0.5, + // ctp_check.mutable_base()->mutable_rotation()->mutable_euler_zyx()->y(), + // 1e-6); EXPECT_NEAR(0.6, + // ctp_check.mutable_base()->mutable_rotation()->mutable_euler_zyx()->z(), + // 1e-6); + // } + { + lebai::posture::Pose pose, pose_check; + pose.mutable_joint()->set_joint({1.0, 2.0, 3.0, 4.0, 5.0, 6.0}); + auto json_str = pose.ToJSONString(); + pose_check.FromJSONString(json_str); + json_str = pose_check.ToJSONString(); + // ASSERT_FALSE(pose_check.mutable_cart()); + ASSERT_EQ(6, pose_check.mutable_joint()->joint().size()); + EXPECT_NEAR(6.0, pose_check.mutable_joint()->joint()[5], 1e-6); + pose.mutable_cart()->mutable_position()->set_x(0.1); + pose.mutable_cart()->mutable_position()->set_y(0.2); + pose.mutable_cart()->mutable_position()->set_z(0.3); + json_str = pose.ToJSONString(); + pose_check.FromJSONString(json_str); + // ASSERT_FALSE(pose_check.joint()); + EXPECT_NEAR(0.1, pose_check.mutable_cart()->position().x(), 1e-6); + EXPECT_NEAR(0.2, pose_check.mutable_cart()->position().y(), 1e-6); + EXPECT_NEAR(0.3, pose_check.mutable_cart()->position().z(), 1e-6); - lebai::motion::SpeedJRequest req, req_check; - *req.mutable_param()->mutable_acc() = 0.1; - *req.mutable_param()->mutable_time() = 0.2; - *req.mutable_param()->mutable_constrained() = true; - req.mutable_speed()->mutable_joint()->push_back(0.1); - req.mutable_speed()->mutable_joint()->push_back(0.2); - req.mutable_speed()->mutable_joint()->push_back(0.3); - req.mutable_speed()->mutable_joint()->push_back(0.4); - req.mutable_speed()->mutable_joint()->push_back(0.5); - req.mutable_speed()->mutable_joint()->push_back(0.6); + // EXPECT_NEAR(0.2, ctp_check.mutable_base()->mutable_position()->y(), + // 1e-6); EXPECT_NEAR(0.3, + // ctp_check.mutable_base()->mutable_position()->z(), 1e-6); + // EXPECT_NEAR(0.4, + // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->x(), 1e-6); + // EXPECT_NEAR(0.5, + // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->y(), 1e-6); + // EXPECT_NEAR(0.6, + // ctp.mutable_base()->mutable_rotation()->mutable_euler_zyx()->z(), 1e-6); + } + { + lebai::posture::Rotation rot, rot_check; + rot.mutable_euler_zyx()->set_x(0.1); + rot.mutable_euler_zyx()->set_y(0.2); + rot.mutable_euler_zyx()->set_z(0.3); + auto json_str = rot.ToJSONString(); + rot_check.FromJSONString(json_str); + EXPECT_NEAR(0.1, rot_check.euler_zyx()->x(), 1e-6); + EXPECT_NEAR(0.2, rot_check.euler_zyx()->y(), 1e-6); + EXPECT_NEAR(0.3, rot_check.euler_zyx()->z(), 1e-6); + // std::cout<<"json_str:"<mutable_cart()->mutable_position()->set_x(0.1); + req.mutable_from()->mutable_cart()->mutable_position()->set_y(0.2); + req.mutable_from()->mutable_cart()->mutable_position()->set_z(0.3); + req.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(0.4); + req.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(0.5); + req.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(0.6); - json_str = req.ToJSONString(); - req_check.FromJSONString(json_str); - EXPECT_NEAR(0.1, *req_check.mutable_param()->mutable_acc(), 1e-6); - EXPECT_NEAR(0.2, *req_check.mutable_param()->mutable_time(), 1e-6); - EXPECT_TRUE(*req_check.mutable_param()->mutable_constrained()); - EXPECT_NEAR(0.1, req_check.mutable_speed()->mutable_joint()->at(0), 1e-6); - EXPECT_NEAR(0.2, req_check.mutable_speed()->mutable_joint()->at(1), 1e-6); - EXPECT_NEAR(0.3, req_check.mutable_speed()->mutable_joint()->at(2), 1e-6); - EXPECT_NEAR(0.4, req_check.mutable_speed()->mutable_joint()->at(3), 1e-6); - EXPECT_NEAR(0.5, req_check.mutable_speed()->mutable_joint()->at(4), 1e-6); - EXPECT_NEAR(0.6, req_check.mutable_speed()->mutable_joint()->at(5), 1e-6); + req.mutable_from_to()->mutable_cart()->mutable_position()->set_x(0.1); + req.mutable_from_to()->mutable_cart()->mutable_position()->set_y(0.2); + req.mutable_from_to()->mutable_cart()->mutable_position()->set_z(0.3); + req.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_x(0.4); + req.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_y(0.5); + req.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->set_z(0.6); + auto json_str = req.ToJSONString(); + req_check.FromJSONString(json_str); + EXPECT_NEAR( + 0.1, req_check.mutable_from()->mutable_cart()->mutable_position()->x(), + 1e-6); + EXPECT_NEAR( + 0.2, req_check.mutable_from()->mutable_cart()->mutable_position()->y(), + 1e-6); + EXPECT_NEAR( + 0.3, req_check.mutable_from()->mutable_cart()->mutable_position()->z(), + 1e-6); + EXPECT_NEAR(0.4, + req_check.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->x(), + 1e-6); + EXPECT_NEAR(0.5, + req_check.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->y(), + 1e-6); + EXPECT_NEAR(0.6, + req_check.mutable_from() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->z(), + 1e-6); - } + EXPECT_NEAR( + 0.1, + req_check.mutable_from_to()->mutable_cart()->mutable_position()->x(), + 1e-6); + EXPECT_NEAR( + 0.2, + req_check.mutable_from_to()->mutable_cart()->mutable_position()->y(), + 1e-6); + EXPECT_NEAR( + 0.3, + req_check.mutable_from_to()->mutable_cart()->mutable_position()->z(), + 1e-6); + EXPECT_NEAR(0.4, + req_check.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->x(), + 1e-6); + EXPECT_NEAR(0.5, + req_check.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->y(), + 1e-6); + EXPECT_NEAR(0.6, + req_check.mutable_from_to() + ->mutable_cart() + ->mutable_rotation() + ->mutable_euler_zyx() + ->z(), + 1e-6); + } + { + lebai::motion::SpeedParam data, data_check; + *data.mutable_acc() = 0.1; + *data.mutable_time() = 0.2; + *data.mutable_constrained() = true; + auto json_str = data.ToJSONString(); + data_check.FromJSONString(json_str); + EXPECT_NEAR(0.1, *data_check.acc(), 1e-6); + EXPECT_NEAR(0.2, *data_check.time(), 1e-6); + EXPECT_TRUE(*data_check.constrained()); + lebai::motion::SpeedJRequest req, req_check; + *req.mutable_param()->mutable_acc() = 0.1; + *req.mutable_param()->mutable_time() = 0.2; + *req.mutable_param()->mutable_constrained() = true; + req.mutable_speed()->mutable_joint()->push_back(0.1); + req.mutable_speed()->mutable_joint()->push_back(0.2); + req.mutable_speed()->mutable_joint()->push_back(0.3); + req.mutable_speed()->mutable_joint()->push_back(0.4); + req.mutable_speed()->mutable_joint()->push_back(0.5); + req.mutable_speed()->mutable_joint()->push_back(0.6); + json_str = req.ToJSONString(); + req_check.FromJSONString(json_str); + EXPECT_NEAR(0.1, *req_check.mutable_param()->mutable_acc(), 1e-6); + EXPECT_NEAR(0.2, *req_check.mutable_param()->mutable_time(), 1e-6); + EXPECT_TRUE(*req_check.mutable_param()->mutable_constrained()); + EXPECT_NEAR(0.1, req_check.mutable_speed()->mutable_joint()->at(0), 1e-6); + EXPECT_NEAR(0.2, req_check.mutable_speed()->mutable_joint()->at(1), 1e-6); + EXPECT_NEAR(0.3, req_check.mutable_speed()->mutable_joint()->at(2), 1e-6); + EXPECT_NEAR(0.4, req_check.mutable_speed()->mutable_joint()->at(3), 1e-6); + EXPECT_NEAR(0.5, req_check.mutable_speed()->mutable_joint()->at(4), 1e-6); + EXPECT_NEAR(0.6, req_check.mutable_speed()->mutable_joint()->at(5), 1e-6); } - TEST_F(ProtosTest, TestMotion) +} +TEST_F(ProtosTest, TestMotion) { { - { - lebai::motion::MovecRequest req, req_check; - req.mutable_pose()->mutable_joint()->set_joint({1.0,2.0,3.0,4.0,5.0,6.0}); - req.mutable_pose_via()->mutable_joint()->set_joint({0.1,0.2,0.3,0.4,0.5,0.6}); - req.mutable_param()->set_acc(0.1); - req.mutable_param()->set_time(0.2); - req.mutable_param()->set_velocity(0.3); - req.set_rad(0.5); - auto json_str = req.ToJSONString(); - req_check.FromJSONString(json_str); - EXPECT_NEAR(1.0, req_check.mutable_pose()->mutable_joint()->joint().at(0), 1e-6); - EXPECT_NEAR(2.0, req_check.mutable_pose()->mutable_joint()->joint().at(1), 1e-6); - EXPECT_NEAR(3.0, req_check.mutable_pose()->mutable_joint()->joint().at(2), 1e-6); - EXPECT_NEAR(4.0, req_check.mutable_pose()->mutable_joint()->joint().at(3), 1e-6); - EXPECT_NEAR(5.0, req_check.mutable_pose()->mutable_joint()->joint().at(4), 1e-6); - EXPECT_NEAR(6.0, req_check.mutable_pose()->mutable_joint()->joint().at(5), 1e-6); - EXPECT_NEAR(0.1, req_check.mutable_pose_via()->mutable_joint()->joint().at(0), 1e-6); - EXPECT_NEAR(0.2, req_check.mutable_pose_via()->mutable_joint()->joint().at(1), 1e-6); - EXPECT_NEAR(0.3, req_check.mutable_pose_via()->mutable_joint()->joint().at(2), 1e-6); - EXPECT_NEAR(0.4, req_check.mutable_pose_via()->mutable_joint()->joint().at(3), 1e-6); - EXPECT_NEAR(0.5, req_check.mutable_pose_via()->mutable_joint()->joint().at(4), 1e-6); - EXPECT_NEAR(0.6, req_check.mutable_pose_via()->mutable_joint()->joint().at(5), 1e-6); - EXPECT_NEAR(0.1, *req_check.mutable_param()->mutable_acc(), 1e-6); - EXPECT_NEAR(0.2, *req_check.mutable_param()->mutable_time(), 1e-6); - EXPECT_NEAR(0.3, *req_check.mutable_param()->mutable_velocity(), 1e-6); - EXPECT_NEAR(0.5, *req_check.mutable_rad(), 1e-6); - } - } + lebai::motion::MovecRequest req, req_check; + req.mutable_pose()->mutable_joint()->set_joint( + {1.0, 2.0, 3.0, 4.0, 5.0, 6.0}); + req.mutable_pose_via()->mutable_joint()->set_joint( + {0.1, 0.2, 0.3, 0.4, 0.5, 0.6}); + req.mutable_param()->set_acc(0.1); + req.mutable_param()->set_time(0.2); + req.mutable_param()->set_velocity(0.3); + req.set_rad(0.5); + auto json_str = req.ToJSONString(); + req_check.FromJSONString(json_str); + EXPECT_NEAR(1.0, req_check.mutable_pose()->mutable_joint()->joint().at(0), + 1e-6); + EXPECT_NEAR(2.0, req_check.mutable_pose()->mutable_joint()->joint().at(1), + 1e-6); + EXPECT_NEAR(3.0, req_check.mutable_pose()->mutable_joint()->joint().at(2), + 1e-6); + EXPECT_NEAR(4.0, req_check.mutable_pose()->mutable_joint()->joint().at(3), + 1e-6); + EXPECT_NEAR(5.0, req_check.mutable_pose()->mutable_joint()->joint().at(4), + 1e-6); + EXPECT_NEAR(6.0, req_check.mutable_pose()->mutable_joint()->joint().at(5), + 1e-6); + EXPECT_NEAR(0.1, + req_check.mutable_pose_via()->mutable_joint()->joint().at(0), + 1e-6); + EXPECT_NEAR(0.2, + req_check.mutable_pose_via()->mutable_joint()->joint().at(1), + 1e-6); + EXPECT_NEAR(0.3, + req_check.mutable_pose_via()->mutable_joint()->joint().at(2), + 1e-6); + EXPECT_NEAR(0.4, + req_check.mutable_pose_via()->mutable_joint()->joint().at(3), + 1e-6); + EXPECT_NEAR(0.5, + req_check.mutable_pose_via()->mutable_joint()->joint().at(4), + 1e-6); + EXPECT_NEAR(0.6, + req_check.mutable_pose_via()->mutable_joint()->joint().at(5), + 1e-6); + EXPECT_NEAR(0.1, *req_check.mutable_param()->mutable_acc(), 1e-6); + EXPECT_NEAR(0.2, *req_check.mutable_param()->mutable_time(), 1e-6); + EXPECT_NEAR(0.3, *req_check.mutable_param()->mutable_velocity(), 1e-6); + EXPECT_NEAR(0.5, *req_check.mutable_rad(), 1e-6); + } } +} // namespace lebai -int main(int argc, char **argv) -{ +int main(int argc, char **argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/sdk/test/test_robot.cc b/sdk/test/test_robot.cc index 7511029..8aa805d 100644 --- a/sdk/test/test_robot.cc +++ b/sdk/test/test_robot.cc @@ -1,300 +1,320 @@ /** * Copyright 2022 lebai.ltd - * + * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. -*/ + */ #include #include #include #include #include "lebai/robot.hh" -namespace lebai -{ - class RobotTest : public ::testing::Test - { - public: - RobotTest() - :robot_(TEST_L_MASTER_IP, true) - { - // std::cout<<"TEST_L_MASTER_IP "< joint_positions(6); - joint_positions[0] = 0.0; - joint_positions[1] = 0.0; - joint_positions[2] = 0.0; - joint_positions[3] = 0.0; - joint_positions[4] = 0.0; - joint_positions[5] = 0.0; - robot_.movej(joint_positions, 1.0, 0.5, 0.0, 0.0); - joint_positions[0] = 0.0; - joint_positions[1] = -60.0 / 180.0 * M_PI; - joint_positions[2] = 80.0 / 180.0 * M_PI; - joint_positions[3] = -10.0 / 180.0 * M_PI; - joint_positions[4] = -60.0 / 180.0 * M_PI; - joint_positions[5] = 0.0; - robot_.movej(joint_positions, 1.0, 0.5, 0.0, 0.0); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - EXPECT_EQ(7, robot_.get_robot_mode()); - robot_.wait_move(); - auto tcp = robot_.get_target_tcp_pose(); - EXPECT_NEAR(tcp["x"], -0.296, 1e-3); - EXPECT_NEAR(tcp["y"], -0.162, 1e-3); - EXPECT_NEAR(tcp["z"], 0.285, 1e-3); - EXPECT_NEAR(tcp["rz"], 60.0 / 180.0 * M_PI, 1e-2); - EXPECT_NEAR(tcp["ry"], -5.0 / 180.0 * M_PI, 1e-2); - EXPECT_NEAR(tcp["rx"], 81.0 / 180.0 * M_PI, 1e-2); - auto jp = robot_.get_target_joint_positions(); - ASSERT_EQ(6, jp.size()); - EXPECT_NEAR(jp[0], joint_positions[0], 1e-3); - EXPECT_NEAR(jp[1], joint_positions[1], 1e-3); - EXPECT_NEAR(jp[2], joint_positions[2], 1e-3); - EXPECT_NEAR(jp[3], joint_positions[3], 1e-3); - EXPECT_NEAR(jp[4], joint_positions[4], 1e-3); - EXPECT_NEAR(jp[5], joint_positions[5], 1e-3); - std::this_thread::sleep_for(std::chrono::milliseconds(200)); - EXPECT_EQ(5, robot_.get_robot_mode()); - robot_.movej({{"x",-0.296},{"y",-0.295},{"z",0.285},{"rx",60.0 / 180.0 * M_PI},{"ry",-5.0 / 180.0 * M_PI},{"rz", 81.0 / 180.0 * M_PI}}, 3.0, 1.0, 0.0, 0.0); - // std::this_thread::sleep_for(std::chrono::milliseconds(100)); - EXPECT_EQ(7, robot_.get_robot_mode()); - robot_.wait_move(0); - tcp = robot_.get_target_tcp_pose(); - EXPECT_NEAR(tcp["x"], -0.296, 1e-3); - EXPECT_NEAR(tcp["y"], -0.295, 1e-3); - EXPECT_NEAR(tcp["z"], 0.285, 1e-3); - EXPECT_NEAR(tcp["rx"], 60.0 / 180.0 * M_PI, 1e-2); - EXPECT_NEAR(tcp["ry"], -5.0 / 180.0 * M_PI, 1e-2); - EXPECT_NEAR(tcp["rz"], 81.0 / 180.0 * M_PI, 1e-2); - joint_positions[0] = 0.0; - joint_positions[1] = -60.0 / 180.0 * M_PI; - joint_positions[2] = 80.0 / 180.0 * M_PI; - joint_positions[3] = -10.0 / 180.0 * M_PI; - joint_positions[4] = -60.0 / 180.0 * M_PI; - joint_positions[5] = 0.0; - robot_.movel(joint_positions, 0.3, 1.0, 0.0, 0.0); - // std::this_thread::sleep_for(std::chrono::milliseconds(100)); - // EXPECT_EQ(7, robot_.get_robot_mode()); - robot_.wait_move(); - ASSERT_EQ(6, jp.size()); - EXPECT_NEAR(jp[0], joint_positions[0], 1e-3); - EXPECT_NEAR(jp[1], joint_positions[1], 1e-3); - EXPECT_NEAR(jp[2], joint_positions[2], 1e-3); - EXPECT_NEAR(jp[3], joint_positions[3], 1e-3); - EXPECT_NEAR(jp[4], joint_positions[4], 1e-3); - EXPECT_NEAR(jp[5], joint_positions[5], 1e-3); - robot_.movel({{"x",-0.306},{"y",-0.295},{"z",0.285},{"rx",60.0 / 180.0 * M_PI},{"ry",-5.0 / 180.0 * M_PI},{"rz", 81.0 / 180.0 * M_PI}}, 1.0, 0.5, 0.0, 0.0); - // std::this_thread::sleep_for(std::chrono::milliseconds(100)); - EXPECT_EQ(7, robot_.get_robot_mode()); - robot_.wait_move(); - tcp = robot_.get_target_tcp_pose(); - EXPECT_NEAR(tcp["x"], -0.306, 1e-3); - EXPECT_NEAR(tcp["y"], -0.295, 1e-3); - EXPECT_NEAR(tcp["z"], 0.285, 1e-3); - EXPECT_NEAR(tcp["rx"], 60.0 / 180.0 * M_PI, 1e-2); - EXPECT_NEAR(tcp["ry"], -5.0 / 180.0 * M_PI, 1e-2); - EXPECT_NEAR(tcp["rz"], 81.0 / 180.0 * M_PI, 1e-2); - std::this_thread::sleep_for(std::chrono::milliseconds(200)); - EXPECT_EQ(5, robot_.get_robot_mode()); - robot_.movej({13.0/ 180.0 * M_PI, -52.0/ 180.0 * M_PI, 86.0/ 180.0 * M_PI, 8.0/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, -11.0/ 180.0 * M_PI}, 1.0, 0.5, 0.0, 0.0); - robot_.movec({3.0/ 180.0 * M_PI, -48.0/ 180.0 * M_PI, 78.0/ 180.0 * M_PI, 9.0/ 180.0 * M_PI, -67.0/ 180.0 * M_PI, -3.0/ 180.0 * M_PI}, - {-28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 * M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI}, - 0.0, 1.0, 0.5, 0.0, 0.0); - robot_.wait_move(); - joint_positions = robot_.get_target_joint_positions(); - ASSERT_EQ(6, joint_positions.size()); - // -28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 * M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI - EXPECT_NEAR(joint_positions[0], -28.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[1], -59.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[2], 96.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[3], -2.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[4], -92.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[5], 16.0/ 180.0 * M_PI, 1e-3); - auto fk_resp = robot_.kinematics_forward(joint_positions); + void SetUp() {} - robot_.movej({13.0/ 180.0 * M_PI, -52.0/ 180.0 * M_PI, 86.0/ 180.0 * M_PI, 8.0/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, -11.0/ 180.0 * M_PI}, 1.0, 0.5, 0.0, 0.0); - robot_.movec({{"x", -0.282541}, {"y", -0.168246}, {"z", 0.265824}, {"rx", 1.27256}, {"ry", -0.206353}, {"rz", 0.937445}}, - {{"x", -0.255832}, {"y", 0.00270435}, {"z", 0.266642}, {"rz", 1.27293}, {"ry", -0.20805}, {"rx", 0.94485}}, - 0.0, 1.0, 0.5, 0.0, 0.0); - robot_.wait_move(); - joint_positions = robot_.get_target_joint_positions(); - ASSERT_EQ(6, joint_positions.size()); - fk_resp = robot_.kinematics_forward(joint_positions); - // -0.255832, 0.00270435, 0.266642, 1.27293, -0.20805, 0.94485 - // -28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 * M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI - EXPECT_NEAR(joint_positions[0], -28.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[1], -59.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[2], 96.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[3], -2.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[4], -92.0/ 180.0 * M_PI, 1e-3); - EXPECT_NEAR(joint_positions[5], 16.0/ 180.0 * M_PI, 1e-3); - // {-28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 * M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI}, - // 0.0, 1.0, 0.5, 0.0, 0.0); -// kinematics_forward: -0.282541, -0.168246, 0.265824, 1.27256, -0.206353, 0.937445 -// kinematics_forward: -0.255832, 0.00270435, 0.266642, 1.27293, -0.20805, 0.94485 - robot_.speedj( 1.0, {0.5,0.0,0.0,0.0,0.0,0.0}, 0.0); - std::this_thread::sleep_for(std::chrono::seconds(2)); - robot_.stop_move(); - robot_.speedl( 1.0, {{"x", 0.0}, {"y", 0.0}, {"z", 0.1}, {"rx", 0.0}, {"ry", 0.0}, {"rz", 0.0}}, 0.0); - std::this_thread::sleep_for(std::chrono::seconds(2)); - robot_.stop_move(); - - - - robot_.towardj({0.0, 0.0, 0.0, 0.0, 0.0, 0.0}, 1.0, 1.0, 0.0, 0.0); - robot_.wait_move(); - joint_positions.clear(); - joint_positions = robot_.get_target_joint_positions(); - ASSERT_EQ(6, joint_positions.size()); - EXPECT_NEAR(joint_positions[0], 0.0, 1e-3); - EXPECT_NEAR(joint_positions[1], 0.0, 1e-3); - EXPECT_NEAR(joint_positions[2], 0.0, 1e-3); - EXPECT_NEAR(joint_positions[3], 0.0, 1e-3); - EXPECT_NEAR(joint_positions[4], 0.0, 1e-3); - EXPECT_NEAR(joint_positions[5], 0.0, 1e-3); - - } - } - TEST_F(RobotTest, TestStatus) - { - robot_.start_sys(); - auto speed = robot_.get_actual_joint_speed(); - EXPECT_EQ(6, speed.size()); - speed = robot_.get_target_joint_speed(); - EXPECT_EQ(6, speed.size()); - auto cart_pose = robot_.get_actual_tcp_pose(); - EXPECT_EQ(6, cart_pose.size()); - cart_pose = robot_.get_target_tcp_pose(); - EXPECT_EQ(6, cart_pose.size()); - robot_.get_joint_temp(0); - auto torques = robot_.get_actual_joint_torques(); - EXPECT_EQ(6, torques.size()); - torques = robot_.get_target_joint_torques(); - EXPECT_EQ(6, torques.size()); - } - TEST_F(RobotTest, TestCabinetIO) - { - robot_.start_sys(); - robot_.set_do("ROBOT",0, static_cast(1)); - robot_.get_di("ROBOT",0); - robot_.set_ao("ROBOT",0, 0.2); - robot_.get_ai("ROBOT",0); - } - TEST_F(RobotTest, TestFlangeIO) - { - robot_.start_sys(); - robot_.get_di("FLANGE", 0); - robot_.set_do("FLANGE", 0, static_cast(1)); - } - TEST_F(RobotTest, TestExtraIO) - { - robot_.start_sys(); - robot_.get_di("EXTRA", 0); - robot_.set_do("EXTRA", 0, static_cast(1)); - robot_.get_ai("EXTRA", 0); - robot_.set_ao("EXTRA", 0, 0.0); - for(unsigned int i = 0; i < 100; ++i) - { - robot_.get_di("EXTRA", 0); - } - } - TEST_F(RobotTest, TestClaw) - { - robot_.start_sys(); - robot_.set_claw(0,0); - auto claw_data = robot_.get_claw(); - } - TEST_F(RobotTest, TestLed) - { - robot_.start_sys(); - robot_.set_led(0,2,{1}); - robot_.set_voice(0,1); - robot_.set_fan(1); - } - TEST_F(RobotTest, TestSignal) - { - robot_.start_sys(); - robot_.set_signal(0,20); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - EXPECT_EQ(20, robot_.get_signal(0)); - robot_.set_signal(0,30); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - EXPECT_EQ(30, robot_.get_signal(0)); - robot_.add_signal(10,50); - robot_.set_signal(10,60); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - EXPECT_EQ(60, robot_.get_signal(10)); - } - TEST_F(RobotTest, TestRobotics) + protected: + l_master::Robot robot_; +}; +TEST_F(RobotTest, TestStartStop) { + robot_.stop_sys(); + std::this_thread::sleep_for(std::chrono::seconds(3)); + robot_.start_sys(); + std::this_thread::sleep_for(std::chrono::seconds(1)); + EXPECT_EQ(5, robot_.get_robot_mode()); + robot_.stop_sys(); + std::this_thread::sleep_for(std::chrono::seconds(5)); + EXPECT_EQ(12, robot_.get_robot_mode()); + robot_.estop(); + std::this_thread::sleep_for(std::chrono::seconds(1)); + EXPECT_EQ(1, robot_.get_robot_mode()); + robot_.start_sys(); + std::this_thread::sleep_for(std::chrono::seconds(1)); + EXPECT_EQ(5, robot_.get_robot_mode()); + robot_.teach_mode(); + std::this_thread::sleep_for(std::chrono::seconds(1)); + EXPECT_EQ(11, robot_.get_robot_mode()); + robot_.end_teach_mode(); + std::this_thread::sleep_for(std::chrono::seconds(1)); + EXPECT_EQ(5, robot_.get_robot_mode()); +} +TEST_F(RobotTest, TestMove) { + robot_.start_sys(); + std::this_thread::sleep_for(std::chrono::seconds(1)); + ASSERT_EQ(5, robot_.get_robot_mode()); { - robot_.start_sys(); std::vector joint_positions(6); joint_positions[0] = 0.0; + joint_positions[1] = 0.0; + joint_positions[2] = 0.0; + joint_positions[3] = 0.0; + joint_positions[4] = 0.0; + joint_positions[5] = 0.0; + robot_.movej(joint_positions, 1.0, 0.5, 0.0, 0.0); + joint_positions[0] = 0.0; + joint_positions[1] = -60.0 / 180.0 * M_PI; + joint_positions[2] = 80.0 / 180.0 * M_PI; + joint_positions[3] = -10.0 / 180.0 * M_PI; + joint_positions[4] = -60.0 / 180.0 * M_PI; + joint_positions[5] = 0.0; + robot_.movej(joint_positions, 1.0, 0.5, 0.0, 0.0); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_EQ(7, robot_.get_robot_mode()); + robot_.wait_move(); + auto tcp = robot_.get_target_tcp_pose(); + EXPECT_NEAR(tcp["x"], -0.296, 1e-3); + EXPECT_NEAR(tcp["y"], -0.162, 1e-3); + EXPECT_NEAR(tcp["z"], 0.285, 1e-3); + EXPECT_NEAR(tcp["rz"], 60.0 / 180.0 * M_PI, 1e-2); + EXPECT_NEAR(tcp["ry"], -5.0 / 180.0 * M_PI, 1e-2); + EXPECT_NEAR(tcp["rx"], 81.0 / 180.0 * M_PI, 1e-2); + auto jp = robot_.get_target_joint_positions(); + ASSERT_EQ(6, jp.size()); + EXPECT_NEAR(jp[0], joint_positions[0], 1e-3); + EXPECT_NEAR(jp[1], joint_positions[1], 1e-3); + EXPECT_NEAR(jp[2], joint_positions[2], 1e-3); + EXPECT_NEAR(jp[3], joint_positions[3], 1e-3); + EXPECT_NEAR(jp[4], joint_positions[4], 1e-3); + EXPECT_NEAR(jp[5], joint_positions[5], 1e-3); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + EXPECT_EQ(5, robot_.get_robot_mode()); + robot_.movej({{"x", -0.296}, + {"y", -0.295}, + {"z", 0.285}, + {"rx", 60.0 / 180.0 * M_PI}, + {"ry", -5.0 / 180.0 * M_PI}, + {"rz", 81.0 / 180.0 * M_PI}}, + 3.0, 1.0, 0.0, 0.0); + // std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_EQ(7, robot_.get_robot_mode()); + robot_.wait_move(0); + tcp = robot_.get_target_tcp_pose(); + EXPECT_NEAR(tcp["x"], -0.296, 1e-3); + EXPECT_NEAR(tcp["y"], -0.295, 1e-3); + EXPECT_NEAR(tcp["z"], 0.285, 1e-3); + EXPECT_NEAR(tcp["rx"], 60.0 / 180.0 * M_PI, 1e-2); + EXPECT_NEAR(tcp["ry"], -5.0 / 180.0 * M_PI, 1e-2); + EXPECT_NEAR(tcp["rz"], 81.0 / 180.0 * M_PI, 1e-2); + joint_positions[0] = 0.0; joint_positions[1] = -60.0 / 180.0 * M_PI; joint_positions[2] = 80.0 / 180.0 * M_PI; joint_positions[3] = -10.0 / 180.0 * M_PI; joint_positions[4] = -60.0 / 180.0 * M_PI; - joint_positions[5] = 0.0; - auto kf_resp = robot_.kinematics_forward(joint_positions); - EXPECT_TRUE(kf_resp.ok); - auto ki_resp = robot_.kinematics_inverse(kf_resp.pose, joint_positions); - EXPECT_TRUE(ki_resp.ok); - kf_resp.pose = robot_.pose_times(kf_resp.pose, kf_resp.pose); - kf_resp.pose = robot_.pose_inverse(kf_resp.pose); + joint_positions[5] = 0.0; + robot_.movel(joint_positions, 0.3, 1.0, 0.0, 0.0); + // std::this_thread::sleep_for(std::chrono::milliseconds(100)); + // EXPECT_EQ(7, robot_.get_robot_mode()); + robot_.wait_move(); + ASSERT_EQ(6, jp.size()); + EXPECT_NEAR(jp[0], joint_positions[0], 1e-3); + EXPECT_NEAR(jp[1], joint_positions[1], 1e-3); + EXPECT_NEAR(jp[2], joint_positions[2], 1e-3); + EXPECT_NEAR(jp[3], joint_positions[3], 1e-3); + EXPECT_NEAR(jp[4], joint_positions[4], 1e-3); + EXPECT_NEAR(jp[5], joint_positions[5], 1e-3); + robot_.movel({{"x", -0.306}, + {"y", -0.295}, + {"z", 0.285}, + {"rx", 60.0 / 180.0 * M_PI}, + {"ry", -5.0 / 180.0 * M_PI}, + {"rz", 81.0 / 180.0 * M_PI}}, + 1.0, 0.5, 0.0, 0.0); + // std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_EQ(7, robot_.get_robot_mode()); + robot_.wait_move(); + tcp = robot_.get_target_tcp_pose(); + EXPECT_NEAR(tcp["x"], -0.306, 1e-3); + EXPECT_NEAR(tcp["y"], -0.295, 1e-3); + EXPECT_NEAR(tcp["z"], 0.285, 1e-3); + EXPECT_NEAR(tcp["rx"], 60.0 / 180.0 * M_PI, 1e-2); + EXPECT_NEAR(tcp["ry"], -5.0 / 180.0 * M_PI, 1e-2); + EXPECT_NEAR(tcp["rz"], 81.0 / 180.0 * M_PI, 1e-2); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + EXPECT_EQ(5, robot_.get_robot_mode()); + robot_.movej( + {13.0 / 180.0 * M_PI, -52.0 / 180.0 * M_PI, 86.0 / 180.0 * M_PI, + 8.0 / 180.0 * M_PI, -59.0 / 180.0 * M_PI, -11.0 / 180.0 * M_PI}, + 1.0, 0.5, 0.0, 0.0); + robot_.movec( + {3.0 / 180.0 * M_PI, -48.0 / 180.0 * M_PI, 78.0 / 180.0 * M_PI, + 9.0 / 180.0 * M_PI, -67.0 / 180.0 * M_PI, -3.0 / 180.0 * M_PI}, + {-28 / 180.0 * M_PI, -59.0 / 180.0 * M_PI, 96.0 / 180.0 * M_PI, + -2.0 / 180.0 * M_PI, -92.0 / 180.0 * M_PI, 16.0 / 180.0 * M_PI}, + 0.0, 1.0, 0.5, 0.0, 0.0); + robot_.wait_move(); + joint_positions = robot_.get_target_joint_positions(); + ASSERT_EQ(6, joint_positions.size()); + // -28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 * + // M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI + EXPECT_NEAR(joint_positions[0], -28.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[1], -59.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[2], 96.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[3], -2.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[4], -92.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[5], 16.0 / 180.0 * M_PI, 1e-3); + auto fk_resp = robot_.kinematics_forward(joint_positions); + + robot_.movej( + {13.0 / 180.0 * M_PI, -52.0 / 180.0 * M_PI, 86.0 / 180.0 * M_PI, + 8.0 / 180.0 * M_PI, -59.0 / 180.0 * M_PI, -11.0 / 180.0 * M_PI}, + 1.0, 0.5, 0.0, 0.0); + robot_.movec({{"x", -0.282541}, + {"y", -0.168246}, + {"z", 0.265824}, + {"rx", 1.27256}, + {"ry", -0.206353}, + {"rz", 0.937445}}, + {{"x", -0.255832}, + {"y", 0.00270435}, + {"z", 0.266642}, + {"rz", 1.27293}, + {"ry", -0.20805}, + {"rx", 0.94485}}, + 0.0, 1.0, 0.5, 0.0, 0.0); + robot_.wait_move(); + joint_positions = robot_.get_target_joint_positions(); + ASSERT_EQ(6, joint_positions.size()); + fk_resp = robot_.kinematics_forward(joint_positions); + // -0.255832, 0.00270435, 0.266642, 1.27293, -0.20805, 0.94485 + // -28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 * + // M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI + EXPECT_NEAR(joint_positions[0], -28.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[1], -59.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[2], 96.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[3], -2.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[4], -92.0 / 180.0 * M_PI, 1e-3); + EXPECT_NEAR(joint_positions[5], 16.0 / 180.0 * M_PI, 1e-3); + // {-28/ 180.0 * M_PI, -59.0/ 180.0 * M_PI, 96.0/ 180.0 * M_PI, -2.0/ 180.0 + // * M_PI, -92.0/ 180.0 * M_PI, 16.0/ 180.0 * M_PI}, + // 0.0, 1.0, 0.5, 0.0, 0.0); + // kinematics_forward: -0.282541, -0.168246, 0.265824, 1.27256, -0.206353, + // 0.937445 kinematics_forward: -0.255832, 0.00270435, 0.266642, 1.27293, + // -0.20805, 0.94485 + robot_.speedj(1.0, {0.5, 0.0, 0.0, 0.0, 0.0, 0.0}, 0.0); + std::this_thread::sleep_for(std::chrono::seconds(2)); + robot_.stop_move(); + robot_.speedl(1.0, + {{"x", 0.0}, + {"y", 0.0}, + {"z", 0.1}, + {"rx", 0.0}, + {"ry", 0.0}, + {"rz", 0.0}}, + 0.0); + std::this_thread::sleep_for(std::chrono::seconds(2)); + robot_.stop_move(); + + robot_.towardj({0.0, 0.0, 0.0, 0.0, 0.0, 0.0}, 1.0, 1.0, 0.0, 0.0); + robot_.wait_move(); + joint_positions.clear(); + joint_positions = robot_.get_target_joint_positions(); + ASSERT_EQ(6, joint_positions.size()); + EXPECT_NEAR(joint_positions[0], 0.0, 1e-3); + EXPECT_NEAR(joint_positions[1], 0.0, 1e-3); + EXPECT_NEAR(joint_positions[2], 0.0, 1e-3); + EXPECT_NEAR(joint_positions[3], 0.0, 1e-3); + EXPECT_NEAR(joint_positions[4], 0.0, 1e-3); + EXPECT_NEAR(joint_positions[5], 0.0, 1e-3); } - TEST_F(RobotTest, TestNetworkConnection) - { - EXPECT_TRUE(robot_.is_network_connected()); +} +TEST_F(RobotTest, TestStatus) { + robot_.start_sys(); + auto speed = robot_.get_actual_joint_speed(); + EXPECT_EQ(6, speed.size()); + speed = robot_.get_target_joint_speed(); + EXPECT_EQ(6, speed.size()); + auto cart_pose = robot_.get_actual_tcp_pose(); + EXPECT_EQ(6, cart_pose.size()); + cart_pose = robot_.get_target_tcp_pose(); + EXPECT_EQ(6, cart_pose.size()); + robot_.get_joint_temp(0); + auto torques = robot_.get_actual_joint_torques(); + EXPECT_EQ(6, torques.size()); + torques = robot_.get_target_joint_torques(); + EXPECT_EQ(6, torques.size()); +} +TEST_F(RobotTest, TestCabinetIO) { + robot_.start_sys(); + robot_.set_do("ROBOT", 0, static_cast(1)); + robot_.get_di("ROBOT", 0); + robot_.set_ao("ROBOT", 0, 0.2); + robot_.get_ai("ROBOT", 0); +} +TEST_F(RobotTest, TestFlangeIO) { + robot_.start_sys(); + robot_.get_di("FLANGE", 0); + robot_.set_do("FLANGE", 0, static_cast(1)); +} +TEST_F(RobotTest, TestExtraIO) { + robot_.start_sys(); + robot_.get_di("EXTRA", 0); + robot_.set_do("EXTRA", 0, static_cast(1)); + robot_.get_ai("EXTRA", 0); + robot_.set_ao("EXTRA", 0, 0.0); + for (unsigned int i = 0; i < 100; ++i) { + robot_.get_di("EXTRA", 0); } } +TEST_F(RobotTest, TestClaw) { + robot_.start_sys(); + robot_.set_claw(0, 0); + auto claw_data = robot_.get_claw(); +} +TEST_F(RobotTest, TestLed) { + robot_.start_sys(); + robot_.set_led(0, 2, {1}); + robot_.set_voice(0, 1); + robot_.set_fan(1); +} +TEST_F(RobotTest, TestSignal) { + robot_.start_sys(); + robot_.set_signal(0, 20); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_EQ(20, robot_.get_signal(0)); + robot_.set_signal(0, 30); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_EQ(30, robot_.get_signal(0)); + robot_.add_signal(10, 50); + robot_.set_signal(10, 60); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_EQ(60, robot_.get_signal(10)); +} +TEST_F(RobotTest, TestRobotics) { + robot_.start_sys(); + std::vector joint_positions(6); + joint_positions[0] = 0.0; + joint_positions[1] = -60.0 / 180.0 * M_PI; + joint_positions[2] = 80.0 / 180.0 * M_PI; + joint_positions[3] = -10.0 / 180.0 * M_PI; + joint_positions[4] = -60.0 / 180.0 * M_PI; + joint_positions[5] = 0.0; + auto kf_resp = robot_.kinematics_forward(joint_positions); + EXPECT_TRUE(kf_resp.ok); + auto ki_resp = robot_.kinematics_inverse(kf_resp.pose, joint_positions); + EXPECT_TRUE(ki_resp.ok); + kf_resp.pose = robot_.pose_times(kf_resp.pose, kf_resp.pose); + kf_resp.pose = robot_.pose_inverse(kf_resp.pose); +} +TEST_F(RobotTest, TestNetworkConnection) { + EXPECT_TRUE(robot_.is_network_connected()); +} +} // namespace lebai -int main(int argc, char **argv) -{ +int main(int argc, char **argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/sdk/third/asio.hpp b/third/asio.hpp similarity index 100% rename from sdk/third/asio.hpp rename to third/asio.hpp diff --git a/sdk/third/asio/any_io_executor.hpp b/third/asio/any_io_executor.hpp similarity index 100% rename from sdk/third/asio/any_io_executor.hpp rename to third/asio/any_io_executor.hpp diff --git a/sdk/third/asio/append.hpp b/third/asio/append.hpp similarity index 100% rename from sdk/third/asio/append.hpp rename to third/asio/append.hpp diff --git a/sdk/third/asio/as_tuple.hpp b/third/asio/as_tuple.hpp similarity index 100% rename from sdk/third/asio/as_tuple.hpp rename to third/asio/as_tuple.hpp diff --git a/sdk/third/asio/associated_allocator.hpp b/third/asio/associated_allocator.hpp similarity index 100% rename from sdk/third/asio/associated_allocator.hpp rename to third/asio/associated_allocator.hpp diff --git a/sdk/third/asio/associated_cancellation_slot.hpp b/third/asio/associated_cancellation_slot.hpp similarity index 100% rename from sdk/third/asio/associated_cancellation_slot.hpp rename to third/asio/associated_cancellation_slot.hpp diff --git a/sdk/third/asio/associated_executor.hpp b/third/asio/associated_executor.hpp similarity index 100% rename from sdk/third/asio/associated_executor.hpp rename to third/asio/associated_executor.hpp diff --git a/sdk/third/asio/associator.hpp b/third/asio/associator.hpp similarity index 100% rename from sdk/third/asio/associator.hpp rename to third/asio/associator.hpp diff --git a/sdk/third/asio/async_result.hpp b/third/asio/async_result.hpp similarity index 100% rename from sdk/third/asio/async_result.hpp rename to third/asio/async_result.hpp diff --git a/sdk/third/asio/awaitable.hpp b/third/asio/awaitable.hpp similarity index 100% rename from sdk/third/asio/awaitable.hpp rename to third/asio/awaitable.hpp diff --git a/sdk/third/asio/basic_datagram_socket.hpp b/third/asio/basic_datagram_socket.hpp similarity index 100% rename from sdk/third/asio/basic_datagram_socket.hpp rename to third/asio/basic_datagram_socket.hpp diff --git a/sdk/third/asio/basic_deadline_timer.hpp b/third/asio/basic_deadline_timer.hpp similarity index 100% rename from sdk/third/asio/basic_deadline_timer.hpp rename to third/asio/basic_deadline_timer.hpp diff --git a/sdk/third/asio/basic_file.hpp b/third/asio/basic_file.hpp similarity index 100% rename from sdk/third/asio/basic_file.hpp rename to third/asio/basic_file.hpp diff --git a/sdk/third/asio/basic_io_object.hpp b/third/asio/basic_io_object.hpp similarity index 100% rename from sdk/third/asio/basic_io_object.hpp rename to third/asio/basic_io_object.hpp diff --git a/sdk/third/asio/basic_random_access_file.hpp b/third/asio/basic_random_access_file.hpp similarity index 100% rename from sdk/third/asio/basic_random_access_file.hpp rename to third/asio/basic_random_access_file.hpp diff --git a/sdk/third/asio/basic_raw_socket.hpp b/third/asio/basic_raw_socket.hpp similarity index 100% rename from sdk/third/asio/basic_raw_socket.hpp rename to third/asio/basic_raw_socket.hpp diff --git a/sdk/third/asio/basic_readable_pipe.hpp b/third/asio/basic_readable_pipe.hpp similarity index 100% rename from sdk/third/asio/basic_readable_pipe.hpp rename to third/asio/basic_readable_pipe.hpp diff --git a/sdk/third/asio/basic_seq_packet_socket.hpp b/third/asio/basic_seq_packet_socket.hpp similarity index 100% rename from sdk/third/asio/basic_seq_packet_socket.hpp rename to third/asio/basic_seq_packet_socket.hpp diff --git a/sdk/third/asio/basic_serial_port.hpp b/third/asio/basic_serial_port.hpp similarity index 100% rename from sdk/third/asio/basic_serial_port.hpp rename to third/asio/basic_serial_port.hpp diff --git a/sdk/third/asio/basic_signal_set.hpp b/third/asio/basic_signal_set.hpp similarity index 100% rename from sdk/third/asio/basic_signal_set.hpp rename to third/asio/basic_signal_set.hpp diff --git a/sdk/third/asio/basic_socket.hpp b/third/asio/basic_socket.hpp similarity index 100% rename from sdk/third/asio/basic_socket.hpp rename to third/asio/basic_socket.hpp diff --git a/sdk/third/asio/basic_socket_acceptor.hpp b/third/asio/basic_socket_acceptor.hpp similarity index 100% rename from sdk/third/asio/basic_socket_acceptor.hpp rename to third/asio/basic_socket_acceptor.hpp diff --git a/sdk/third/asio/basic_socket_iostream.hpp b/third/asio/basic_socket_iostream.hpp similarity index 100% rename from sdk/third/asio/basic_socket_iostream.hpp rename to third/asio/basic_socket_iostream.hpp diff --git a/sdk/third/asio/basic_socket_streambuf.hpp b/third/asio/basic_socket_streambuf.hpp similarity index 100% rename from sdk/third/asio/basic_socket_streambuf.hpp rename to third/asio/basic_socket_streambuf.hpp diff --git a/sdk/third/asio/basic_stream_file.hpp b/third/asio/basic_stream_file.hpp similarity index 100% rename from sdk/third/asio/basic_stream_file.hpp rename to third/asio/basic_stream_file.hpp diff --git a/sdk/third/asio/basic_stream_socket.hpp b/third/asio/basic_stream_socket.hpp similarity index 100% rename from sdk/third/asio/basic_stream_socket.hpp rename to third/asio/basic_stream_socket.hpp diff --git a/sdk/third/asio/basic_streambuf.hpp b/third/asio/basic_streambuf.hpp similarity index 100% rename from sdk/third/asio/basic_streambuf.hpp rename to third/asio/basic_streambuf.hpp diff --git a/sdk/third/asio/basic_streambuf_fwd.hpp b/third/asio/basic_streambuf_fwd.hpp similarity index 100% rename from sdk/third/asio/basic_streambuf_fwd.hpp rename to third/asio/basic_streambuf_fwd.hpp diff --git a/sdk/third/asio/basic_waitable_timer.hpp b/third/asio/basic_waitable_timer.hpp similarity index 100% rename from sdk/third/asio/basic_waitable_timer.hpp rename to third/asio/basic_waitable_timer.hpp diff --git a/sdk/third/asio/basic_writable_pipe.hpp b/third/asio/basic_writable_pipe.hpp similarity index 100% rename from sdk/third/asio/basic_writable_pipe.hpp rename to third/asio/basic_writable_pipe.hpp diff --git a/sdk/third/asio/bind_allocator.hpp b/third/asio/bind_allocator.hpp similarity index 100% rename from sdk/third/asio/bind_allocator.hpp rename to third/asio/bind_allocator.hpp diff --git a/sdk/third/asio/bind_cancellation_slot.hpp b/third/asio/bind_cancellation_slot.hpp similarity index 100% rename from sdk/third/asio/bind_cancellation_slot.hpp rename to third/asio/bind_cancellation_slot.hpp diff --git a/sdk/third/asio/bind_executor.hpp b/third/asio/bind_executor.hpp similarity index 100% rename from sdk/third/asio/bind_executor.hpp rename to third/asio/bind_executor.hpp diff --git a/sdk/third/asio/buffer.hpp b/third/asio/buffer.hpp similarity index 100% rename from sdk/third/asio/buffer.hpp rename to third/asio/buffer.hpp diff --git a/sdk/third/asio/buffer_registration.hpp b/third/asio/buffer_registration.hpp similarity index 100% rename from sdk/third/asio/buffer_registration.hpp rename to third/asio/buffer_registration.hpp diff --git a/sdk/third/asio/buffered_read_stream.hpp b/third/asio/buffered_read_stream.hpp similarity index 100% rename from sdk/third/asio/buffered_read_stream.hpp rename to third/asio/buffered_read_stream.hpp diff --git a/sdk/third/asio/buffered_read_stream_fwd.hpp b/third/asio/buffered_read_stream_fwd.hpp similarity index 100% rename from sdk/third/asio/buffered_read_stream_fwd.hpp rename to third/asio/buffered_read_stream_fwd.hpp diff --git a/sdk/third/asio/buffered_stream.hpp b/third/asio/buffered_stream.hpp similarity index 100% rename from sdk/third/asio/buffered_stream.hpp rename to third/asio/buffered_stream.hpp diff --git a/sdk/third/asio/buffered_stream_fwd.hpp b/third/asio/buffered_stream_fwd.hpp similarity index 100% rename from sdk/third/asio/buffered_stream_fwd.hpp rename to third/asio/buffered_stream_fwd.hpp diff --git a/sdk/third/asio/buffered_write_stream.hpp b/third/asio/buffered_write_stream.hpp similarity index 100% rename from sdk/third/asio/buffered_write_stream.hpp rename to third/asio/buffered_write_stream.hpp diff --git a/sdk/third/asio/buffered_write_stream_fwd.hpp b/third/asio/buffered_write_stream_fwd.hpp similarity index 100% rename from sdk/third/asio/buffered_write_stream_fwd.hpp rename to third/asio/buffered_write_stream_fwd.hpp diff --git a/sdk/third/asio/buffers_iterator.hpp b/third/asio/buffers_iterator.hpp similarity index 100% rename from sdk/third/asio/buffers_iterator.hpp rename to third/asio/buffers_iterator.hpp diff --git a/sdk/third/asio/cancellation_signal.hpp b/third/asio/cancellation_signal.hpp similarity index 100% rename from sdk/third/asio/cancellation_signal.hpp rename to third/asio/cancellation_signal.hpp diff --git a/sdk/third/asio/cancellation_state.hpp b/third/asio/cancellation_state.hpp similarity index 100% rename from sdk/third/asio/cancellation_state.hpp rename to third/asio/cancellation_state.hpp diff --git a/sdk/third/asio/cancellation_type.hpp b/third/asio/cancellation_type.hpp similarity index 100% rename from sdk/third/asio/cancellation_type.hpp rename to third/asio/cancellation_type.hpp diff --git a/sdk/third/asio/co_spawn.hpp b/third/asio/co_spawn.hpp similarity index 100% rename from sdk/third/asio/co_spawn.hpp rename to third/asio/co_spawn.hpp diff --git a/sdk/third/asio/completion_condition.hpp b/third/asio/completion_condition.hpp similarity index 100% rename from sdk/third/asio/completion_condition.hpp rename to third/asio/completion_condition.hpp diff --git a/sdk/third/asio/compose.hpp b/third/asio/compose.hpp similarity index 100% rename from sdk/third/asio/compose.hpp rename to third/asio/compose.hpp diff --git a/sdk/third/asio/connect.hpp b/third/asio/connect.hpp similarity index 100% rename from sdk/third/asio/connect.hpp rename to third/asio/connect.hpp diff --git a/sdk/third/asio/connect_pipe.hpp b/third/asio/connect_pipe.hpp similarity index 100% rename from sdk/third/asio/connect_pipe.hpp rename to third/asio/connect_pipe.hpp diff --git a/sdk/third/asio/coroutine.hpp b/third/asio/coroutine.hpp similarity index 100% rename from sdk/third/asio/coroutine.hpp rename to third/asio/coroutine.hpp diff --git a/sdk/third/asio/deadline_timer.hpp b/third/asio/deadline_timer.hpp similarity index 100% rename from sdk/third/asio/deadline_timer.hpp rename to third/asio/deadline_timer.hpp diff --git a/sdk/third/asio/defer.hpp b/third/asio/defer.hpp similarity index 100% rename from sdk/third/asio/defer.hpp rename to third/asio/defer.hpp diff --git a/sdk/third/asio/deferred.hpp b/third/asio/deferred.hpp similarity index 100% rename from sdk/third/asio/deferred.hpp rename to third/asio/deferred.hpp diff --git a/sdk/third/asio/detached.hpp b/third/asio/detached.hpp similarity index 100% rename from sdk/third/asio/detached.hpp rename to third/asio/detached.hpp diff --git a/sdk/third/asio/detail/array.hpp b/third/asio/detail/array.hpp similarity index 100% rename from sdk/third/asio/detail/array.hpp rename to third/asio/detail/array.hpp diff --git a/sdk/third/asio/detail/array_fwd.hpp b/third/asio/detail/array_fwd.hpp similarity index 100% rename from sdk/third/asio/detail/array_fwd.hpp rename to third/asio/detail/array_fwd.hpp diff --git a/sdk/third/asio/detail/assert.hpp b/third/asio/detail/assert.hpp similarity index 100% rename from sdk/third/asio/detail/assert.hpp rename to third/asio/detail/assert.hpp diff --git a/sdk/third/asio/detail/atomic_count.hpp b/third/asio/detail/atomic_count.hpp similarity index 100% rename from sdk/third/asio/detail/atomic_count.hpp rename to third/asio/detail/atomic_count.hpp diff --git a/sdk/third/asio/detail/base_from_cancellation_state.hpp b/third/asio/detail/base_from_cancellation_state.hpp similarity index 100% rename from sdk/third/asio/detail/base_from_cancellation_state.hpp rename to third/asio/detail/base_from_cancellation_state.hpp diff --git a/sdk/third/asio/detail/base_from_completion_cond.hpp b/third/asio/detail/base_from_completion_cond.hpp similarity index 100% rename from sdk/third/asio/detail/base_from_completion_cond.hpp rename to third/asio/detail/base_from_completion_cond.hpp diff --git a/sdk/third/asio/detail/bind_handler.hpp b/third/asio/detail/bind_handler.hpp similarity index 100% rename from sdk/third/asio/detail/bind_handler.hpp rename to third/asio/detail/bind_handler.hpp diff --git a/sdk/third/asio/detail/blocking_executor_op.hpp b/third/asio/detail/blocking_executor_op.hpp similarity index 100% rename from sdk/third/asio/detail/blocking_executor_op.hpp rename to third/asio/detail/blocking_executor_op.hpp diff --git a/sdk/third/asio/detail/buffer_resize_guard.hpp b/third/asio/detail/buffer_resize_guard.hpp similarity index 100% rename from sdk/third/asio/detail/buffer_resize_guard.hpp rename to third/asio/detail/buffer_resize_guard.hpp diff --git a/sdk/third/asio/detail/buffer_sequence_adapter.hpp b/third/asio/detail/buffer_sequence_adapter.hpp similarity index 100% rename from sdk/third/asio/detail/buffer_sequence_adapter.hpp rename to third/asio/detail/buffer_sequence_adapter.hpp diff --git a/sdk/third/asio/detail/buffered_stream_storage.hpp b/third/asio/detail/buffered_stream_storage.hpp similarity index 100% rename from sdk/third/asio/detail/buffered_stream_storage.hpp rename to third/asio/detail/buffered_stream_storage.hpp diff --git a/sdk/third/asio/detail/bulk_executor_op.hpp b/third/asio/detail/bulk_executor_op.hpp similarity index 100% rename from sdk/third/asio/detail/bulk_executor_op.hpp rename to third/asio/detail/bulk_executor_op.hpp diff --git a/sdk/third/asio/detail/call_stack.hpp b/third/asio/detail/call_stack.hpp similarity index 100% rename from sdk/third/asio/detail/call_stack.hpp rename to third/asio/detail/call_stack.hpp diff --git a/sdk/third/asio/detail/chrono.hpp b/third/asio/detail/chrono.hpp similarity index 100% rename from sdk/third/asio/detail/chrono.hpp rename to third/asio/detail/chrono.hpp diff --git a/sdk/third/asio/detail/chrono_time_traits.hpp b/third/asio/detail/chrono_time_traits.hpp similarity index 100% rename from sdk/third/asio/detail/chrono_time_traits.hpp rename to third/asio/detail/chrono_time_traits.hpp diff --git a/sdk/third/asio/detail/completion_handler.hpp b/third/asio/detail/completion_handler.hpp similarity index 100% rename from sdk/third/asio/detail/completion_handler.hpp rename to third/asio/detail/completion_handler.hpp diff --git a/sdk/third/asio/detail/concurrency_hint.hpp b/third/asio/detail/concurrency_hint.hpp similarity index 100% rename from sdk/third/asio/detail/concurrency_hint.hpp rename to third/asio/detail/concurrency_hint.hpp diff --git a/sdk/third/asio/detail/conditionally_enabled_event.hpp b/third/asio/detail/conditionally_enabled_event.hpp similarity index 100% rename from sdk/third/asio/detail/conditionally_enabled_event.hpp rename to third/asio/detail/conditionally_enabled_event.hpp diff --git a/sdk/third/asio/detail/conditionally_enabled_mutex.hpp b/third/asio/detail/conditionally_enabled_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/conditionally_enabled_mutex.hpp rename to third/asio/detail/conditionally_enabled_mutex.hpp diff --git a/sdk/third/asio/detail/config.hpp b/third/asio/detail/config.hpp similarity index 100% rename from sdk/third/asio/detail/config.hpp rename to third/asio/detail/config.hpp diff --git a/sdk/third/asio/detail/consuming_buffers.hpp b/third/asio/detail/consuming_buffers.hpp similarity index 100% rename from sdk/third/asio/detail/consuming_buffers.hpp rename to third/asio/detail/consuming_buffers.hpp diff --git a/sdk/third/asio/detail/cstddef.hpp b/third/asio/detail/cstddef.hpp similarity index 100% rename from sdk/third/asio/detail/cstddef.hpp rename to third/asio/detail/cstddef.hpp diff --git a/sdk/third/asio/detail/cstdint.hpp b/third/asio/detail/cstdint.hpp similarity index 100% rename from sdk/third/asio/detail/cstdint.hpp rename to third/asio/detail/cstdint.hpp diff --git a/sdk/third/asio/detail/date_time_fwd.hpp b/third/asio/detail/date_time_fwd.hpp similarity index 100% rename from sdk/third/asio/detail/date_time_fwd.hpp rename to third/asio/detail/date_time_fwd.hpp diff --git a/sdk/third/asio/detail/deadline_timer_service.hpp b/third/asio/detail/deadline_timer_service.hpp similarity index 100% rename from sdk/third/asio/detail/deadline_timer_service.hpp rename to third/asio/detail/deadline_timer_service.hpp diff --git a/sdk/third/asio/detail/dependent_type.hpp b/third/asio/detail/dependent_type.hpp similarity index 100% rename from sdk/third/asio/detail/dependent_type.hpp rename to third/asio/detail/dependent_type.hpp diff --git a/sdk/third/asio/detail/descriptor_ops.hpp b/third/asio/detail/descriptor_ops.hpp similarity index 100% rename from sdk/third/asio/detail/descriptor_ops.hpp rename to third/asio/detail/descriptor_ops.hpp diff --git a/sdk/third/asio/detail/descriptor_read_op.hpp b/third/asio/detail/descriptor_read_op.hpp similarity index 100% rename from sdk/third/asio/detail/descriptor_read_op.hpp rename to third/asio/detail/descriptor_read_op.hpp diff --git a/sdk/third/asio/detail/descriptor_write_op.hpp b/third/asio/detail/descriptor_write_op.hpp similarity index 100% rename from sdk/third/asio/detail/descriptor_write_op.hpp rename to third/asio/detail/descriptor_write_op.hpp diff --git a/sdk/third/asio/detail/dev_poll_reactor.hpp b/third/asio/detail/dev_poll_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/dev_poll_reactor.hpp rename to third/asio/detail/dev_poll_reactor.hpp diff --git a/sdk/third/asio/detail/epoll_reactor.hpp b/third/asio/detail/epoll_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/epoll_reactor.hpp rename to third/asio/detail/epoll_reactor.hpp diff --git a/sdk/third/asio/detail/event.hpp b/third/asio/detail/event.hpp similarity index 100% rename from sdk/third/asio/detail/event.hpp rename to third/asio/detail/event.hpp diff --git a/sdk/third/asio/detail/eventfd_select_interrupter.hpp b/third/asio/detail/eventfd_select_interrupter.hpp similarity index 100% rename from sdk/third/asio/detail/eventfd_select_interrupter.hpp rename to third/asio/detail/eventfd_select_interrupter.hpp diff --git a/sdk/third/asio/detail/exception.hpp b/third/asio/detail/exception.hpp similarity index 100% rename from sdk/third/asio/detail/exception.hpp rename to third/asio/detail/exception.hpp diff --git a/sdk/third/asio/detail/executor_function.hpp b/third/asio/detail/executor_function.hpp similarity index 100% rename from sdk/third/asio/detail/executor_function.hpp rename to third/asio/detail/executor_function.hpp diff --git a/sdk/third/asio/detail/executor_op.hpp b/third/asio/detail/executor_op.hpp similarity index 100% rename from sdk/third/asio/detail/executor_op.hpp rename to third/asio/detail/executor_op.hpp diff --git a/sdk/third/asio/detail/fd_set_adapter.hpp b/third/asio/detail/fd_set_adapter.hpp similarity index 100% rename from sdk/third/asio/detail/fd_set_adapter.hpp rename to third/asio/detail/fd_set_adapter.hpp diff --git a/sdk/third/asio/detail/fenced_block.hpp b/third/asio/detail/fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/fenced_block.hpp rename to third/asio/detail/fenced_block.hpp diff --git a/sdk/third/asio/detail/functional.hpp b/third/asio/detail/functional.hpp similarity index 100% rename from sdk/third/asio/detail/functional.hpp rename to third/asio/detail/functional.hpp diff --git a/sdk/third/asio/detail/future.hpp b/third/asio/detail/future.hpp similarity index 100% rename from sdk/third/asio/detail/future.hpp rename to third/asio/detail/future.hpp diff --git a/sdk/third/asio/detail/gcc_arm_fenced_block.hpp b/third/asio/detail/gcc_arm_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/gcc_arm_fenced_block.hpp rename to third/asio/detail/gcc_arm_fenced_block.hpp diff --git a/sdk/third/asio/detail/gcc_hppa_fenced_block.hpp b/third/asio/detail/gcc_hppa_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/gcc_hppa_fenced_block.hpp rename to third/asio/detail/gcc_hppa_fenced_block.hpp diff --git a/sdk/third/asio/detail/gcc_sync_fenced_block.hpp b/third/asio/detail/gcc_sync_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/gcc_sync_fenced_block.hpp rename to third/asio/detail/gcc_sync_fenced_block.hpp diff --git a/sdk/third/asio/detail/gcc_x86_fenced_block.hpp b/third/asio/detail/gcc_x86_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/gcc_x86_fenced_block.hpp rename to third/asio/detail/gcc_x86_fenced_block.hpp diff --git a/sdk/third/asio/detail/global.hpp b/third/asio/detail/global.hpp similarity index 100% rename from sdk/third/asio/detail/global.hpp rename to third/asio/detail/global.hpp diff --git a/sdk/third/asio/detail/handler_alloc_helpers.hpp b/third/asio/detail/handler_alloc_helpers.hpp similarity index 100% rename from sdk/third/asio/detail/handler_alloc_helpers.hpp rename to third/asio/detail/handler_alloc_helpers.hpp diff --git a/sdk/third/asio/detail/handler_cont_helpers.hpp b/third/asio/detail/handler_cont_helpers.hpp similarity index 100% rename from sdk/third/asio/detail/handler_cont_helpers.hpp rename to third/asio/detail/handler_cont_helpers.hpp diff --git a/sdk/third/asio/detail/handler_invoke_helpers.hpp b/third/asio/detail/handler_invoke_helpers.hpp similarity index 100% rename from sdk/third/asio/detail/handler_invoke_helpers.hpp rename to third/asio/detail/handler_invoke_helpers.hpp diff --git a/sdk/third/asio/detail/handler_tracking.hpp b/third/asio/detail/handler_tracking.hpp similarity index 100% rename from sdk/third/asio/detail/handler_tracking.hpp rename to third/asio/detail/handler_tracking.hpp diff --git a/sdk/third/asio/detail/handler_type_requirements.hpp b/third/asio/detail/handler_type_requirements.hpp similarity index 100% rename from sdk/third/asio/detail/handler_type_requirements.hpp rename to third/asio/detail/handler_type_requirements.hpp diff --git a/sdk/third/asio/detail/handler_work.hpp b/third/asio/detail/handler_work.hpp similarity index 100% rename from sdk/third/asio/detail/handler_work.hpp rename to third/asio/detail/handler_work.hpp diff --git a/sdk/third/asio/detail/hash_map.hpp b/third/asio/detail/hash_map.hpp similarity index 100% rename from sdk/third/asio/detail/hash_map.hpp rename to third/asio/detail/hash_map.hpp diff --git a/sdk/third/asio/detail/impl/buffer_sequence_adapter.ipp b/third/asio/detail/impl/buffer_sequence_adapter.ipp similarity index 100% rename from sdk/third/asio/detail/impl/buffer_sequence_adapter.ipp rename to third/asio/detail/impl/buffer_sequence_adapter.ipp diff --git a/sdk/third/asio/detail/impl/descriptor_ops.ipp b/third/asio/detail/impl/descriptor_ops.ipp similarity index 100% rename from sdk/third/asio/detail/impl/descriptor_ops.ipp rename to third/asio/detail/impl/descriptor_ops.ipp diff --git a/sdk/third/asio/detail/impl/dev_poll_reactor.hpp b/third/asio/detail/impl/dev_poll_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/impl/dev_poll_reactor.hpp rename to third/asio/detail/impl/dev_poll_reactor.hpp diff --git a/sdk/third/asio/detail/impl/dev_poll_reactor.ipp b/third/asio/detail/impl/dev_poll_reactor.ipp similarity index 100% rename from sdk/third/asio/detail/impl/dev_poll_reactor.ipp rename to third/asio/detail/impl/dev_poll_reactor.ipp diff --git a/sdk/third/asio/detail/impl/epoll_reactor.hpp b/third/asio/detail/impl/epoll_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/impl/epoll_reactor.hpp rename to third/asio/detail/impl/epoll_reactor.hpp diff --git a/sdk/third/asio/detail/impl/epoll_reactor.ipp b/third/asio/detail/impl/epoll_reactor.ipp similarity index 100% rename from sdk/third/asio/detail/impl/epoll_reactor.ipp rename to third/asio/detail/impl/epoll_reactor.ipp diff --git a/sdk/third/asio/detail/impl/eventfd_select_interrupter.ipp b/third/asio/detail/impl/eventfd_select_interrupter.ipp similarity index 100% rename from sdk/third/asio/detail/impl/eventfd_select_interrupter.ipp rename to third/asio/detail/impl/eventfd_select_interrupter.ipp diff --git a/sdk/third/asio/detail/impl/handler_tracking.ipp b/third/asio/detail/impl/handler_tracking.ipp similarity index 100% rename from sdk/third/asio/detail/impl/handler_tracking.ipp rename to third/asio/detail/impl/handler_tracking.ipp diff --git a/sdk/third/asio/detail/impl/io_uring_descriptor_service.ipp b/third/asio/detail/impl/io_uring_descriptor_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/io_uring_descriptor_service.ipp rename to third/asio/detail/impl/io_uring_descriptor_service.ipp diff --git a/sdk/third/asio/detail/impl/io_uring_file_service.ipp b/third/asio/detail/impl/io_uring_file_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/io_uring_file_service.ipp rename to third/asio/detail/impl/io_uring_file_service.ipp diff --git a/sdk/third/asio/detail/impl/io_uring_service.hpp b/third/asio/detail/impl/io_uring_service.hpp similarity index 100% rename from sdk/third/asio/detail/impl/io_uring_service.hpp rename to third/asio/detail/impl/io_uring_service.hpp diff --git a/sdk/third/asio/detail/impl/io_uring_service.ipp b/third/asio/detail/impl/io_uring_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/io_uring_service.ipp rename to third/asio/detail/impl/io_uring_service.ipp diff --git a/sdk/third/asio/detail/impl/io_uring_socket_service_base.ipp b/third/asio/detail/impl/io_uring_socket_service_base.ipp similarity index 100% rename from sdk/third/asio/detail/impl/io_uring_socket_service_base.ipp rename to third/asio/detail/impl/io_uring_socket_service_base.ipp diff --git a/sdk/third/asio/detail/impl/kqueue_reactor.hpp b/third/asio/detail/impl/kqueue_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/impl/kqueue_reactor.hpp rename to third/asio/detail/impl/kqueue_reactor.hpp diff --git a/sdk/third/asio/detail/impl/kqueue_reactor.ipp b/third/asio/detail/impl/kqueue_reactor.ipp similarity index 100% rename from sdk/third/asio/detail/impl/kqueue_reactor.ipp rename to third/asio/detail/impl/kqueue_reactor.ipp diff --git a/sdk/third/asio/detail/impl/null_event.ipp b/third/asio/detail/impl/null_event.ipp similarity index 100% rename from sdk/third/asio/detail/impl/null_event.ipp rename to third/asio/detail/impl/null_event.ipp diff --git a/sdk/third/asio/detail/impl/pipe_select_interrupter.ipp b/third/asio/detail/impl/pipe_select_interrupter.ipp similarity index 100% rename from sdk/third/asio/detail/impl/pipe_select_interrupter.ipp rename to third/asio/detail/impl/pipe_select_interrupter.ipp diff --git a/sdk/third/asio/detail/impl/posix_event.ipp b/third/asio/detail/impl/posix_event.ipp similarity index 100% rename from sdk/third/asio/detail/impl/posix_event.ipp rename to third/asio/detail/impl/posix_event.ipp diff --git a/sdk/third/asio/detail/impl/posix_mutex.ipp b/third/asio/detail/impl/posix_mutex.ipp similarity index 100% rename from sdk/third/asio/detail/impl/posix_mutex.ipp rename to third/asio/detail/impl/posix_mutex.ipp diff --git a/sdk/third/asio/detail/impl/posix_serial_port_service.ipp b/third/asio/detail/impl/posix_serial_port_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/posix_serial_port_service.ipp rename to third/asio/detail/impl/posix_serial_port_service.ipp diff --git a/sdk/third/asio/detail/impl/posix_thread.ipp b/third/asio/detail/impl/posix_thread.ipp similarity index 100% rename from sdk/third/asio/detail/impl/posix_thread.ipp rename to third/asio/detail/impl/posix_thread.ipp diff --git a/sdk/third/asio/detail/impl/posix_tss_ptr.ipp b/third/asio/detail/impl/posix_tss_ptr.ipp similarity index 100% rename from sdk/third/asio/detail/impl/posix_tss_ptr.ipp rename to third/asio/detail/impl/posix_tss_ptr.ipp diff --git a/sdk/third/asio/detail/impl/reactive_descriptor_service.ipp b/third/asio/detail/impl/reactive_descriptor_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/reactive_descriptor_service.ipp rename to third/asio/detail/impl/reactive_descriptor_service.ipp diff --git a/sdk/third/asio/detail/impl/reactive_socket_service_base.ipp b/third/asio/detail/impl/reactive_socket_service_base.ipp similarity index 100% rename from sdk/third/asio/detail/impl/reactive_socket_service_base.ipp rename to third/asio/detail/impl/reactive_socket_service_base.ipp diff --git a/sdk/third/asio/detail/impl/resolver_service_base.ipp b/third/asio/detail/impl/resolver_service_base.ipp similarity index 100% rename from sdk/third/asio/detail/impl/resolver_service_base.ipp rename to third/asio/detail/impl/resolver_service_base.ipp diff --git a/sdk/third/asio/detail/impl/scheduler.ipp b/third/asio/detail/impl/scheduler.ipp similarity index 100% rename from sdk/third/asio/detail/impl/scheduler.ipp rename to third/asio/detail/impl/scheduler.ipp diff --git a/sdk/third/asio/detail/impl/select_reactor.hpp b/third/asio/detail/impl/select_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/impl/select_reactor.hpp rename to third/asio/detail/impl/select_reactor.hpp diff --git a/sdk/third/asio/detail/impl/select_reactor.ipp b/third/asio/detail/impl/select_reactor.ipp similarity index 100% rename from sdk/third/asio/detail/impl/select_reactor.ipp rename to third/asio/detail/impl/select_reactor.ipp diff --git a/sdk/third/asio/detail/impl/service_registry.hpp b/third/asio/detail/impl/service_registry.hpp similarity index 100% rename from sdk/third/asio/detail/impl/service_registry.hpp rename to third/asio/detail/impl/service_registry.hpp diff --git a/sdk/third/asio/detail/impl/service_registry.ipp b/third/asio/detail/impl/service_registry.ipp similarity index 100% rename from sdk/third/asio/detail/impl/service_registry.ipp rename to third/asio/detail/impl/service_registry.ipp diff --git a/sdk/third/asio/detail/impl/signal_set_service.ipp b/third/asio/detail/impl/signal_set_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/signal_set_service.ipp rename to third/asio/detail/impl/signal_set_service.ipp diff --git a/sdk/third/asio/detail/impl/socket_ops.ipp b/third/asio/detail/impl/socket_ops.ipp similarity index 100% rename from sdk/third/asio/detail/impl/socket_ops.ipp rename to third/asio/detail/impl/socket_ops.ipp diff --git a/sdk/third/asio/detail/impl/socket_select_interrupter.ipp b/third/asio/detail/impl/socket_select_interrupter.ipp similarity index 100% rename from sdk/third/asio/detail/impl/socket_select_interrupter.ipp rename to third/asio/detail/impl/socket_select_interrupter.ipp diff --git a/sdk/third/asio/detail/impl/strand_executor_service.hpp b/third/asio/detail/impl/strand_executor_service.hpp similarity index 100% rename from sdk/third/asio/detail/impl/strand_executor_service.hpp rename to third/asio/detail/impl/strand_executor_service.hpp diff --git a/sdk/third/asio/detail/impl/strand_executor_service.ipp b/third/asio/detail/impl/strand_executor_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/strand_executor_service.ipp rename to third/asio/detail/impl/strand_executor_service.ipp diff --git a/sdk/third/asio/detail/impl/strand_service.hpp b/third/asio/detail/impl/strand_service.hpp similarity index 100% rename from sdk/third/asio/detail/impl/strand_service.hpp rename to third/asio/detail/impl/strand_service.hpp diff --git a/sdk/third/asio/detail/impl/strand_service.ipp b/third/asio/detail/impl/strand_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/strand_service.ipp rename to third/asio/detail/impl/strand_service.ipp diff --git a/sdk/third/asio/detail/impl/thread_context.ipp b/third/asio/detail/impl/thread_context.ipp similarity index 100% rename from sdk/third/asio/detail/impl/thread_context.ipp rename to third/asio/detail/impl/thread_context.ipp diff --git a/sdk/third/asio/detail/impl/throw_error.ipp b/third/asio/detail/impl/throw_error.ipp similarity index 100% rename from sdk/third/asio/detail/impl/throw_error.ipp rename to third/asio/detail/impl/throw_error.ipp diff --git a/sdk/third/asio/detail/impl/timer_queue_ptime.ipp b/third/asio/detail/impl/timer_queue_ptime.ipp similarity index 100% rename from sdk/third/asio/detail/impl/timer_queue_ptime.ipp rename to third/asio/detail/impl/timer_queue_ptime.ipp diff --git a/sdk/third/asio/detail/impl/timer_queue_set.ipp b/third/asio/detail/impl/timer_queue_set.ipp similarity index 100% rename from sdk/third/asio/detail/impl/timer_queue_set.ipp rename to third/asio/detail/impl/timer_queue_set.ipp diff --git a/sdk/third/asio/detail/impl/win_event.ipp b/third/asio/detail/impl/win_event.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_event.ipp rename to third/asio/detail/impl/win_event.ipp diff --git a/sdk/third/asio/detail/impl/win_iocp_file_service.ipp b/third/asio/detail/impl/win_iocp_file_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_iocp_file_service.ipp rename to third/asio/detail/impl/win_iocp_file_service.ipp diff --git a/sdk/third/asio/detail/impl/win_iocp_handle_service.ipp b/third/asio/detail/impl/win_iocp_handle_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_iocp_handle_service.ipp rename to third/asio/detail/impl/win_iocp_handle_service.ipp diff --git a/sdk/third/asio/detail/impl/win_iocp_io_context.hpp b/third/asio/detail/impl/win_iocp_io_context.hpp similarity index 100% rename from sdk/third/asio/detail/impl/win_iocp_io_context.hpp rename to third/asio/detail/impl/win_iocp_io_context.hpp diff --git a/sdk/third/asio/detail/impl/win_iocp_io_context.ipp b/third/asio/detail/impl/win_iocp_io_context.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_iocp_io_context.ipp rename to third/asio/detail/impl/win_iocp_io_context.ipp diff --git a/sdk/third/asio/detail/impl/win_iocp_serial_port_service.ipp b/third/asio/detail/impl/win_iocp_serial_port_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_iocp_serial_port_service.ipp rename to third/asio/detail/impl/win_iocp_serial_port_service.ipp diff --git a/sdk/third/asio/detail/impl/win_iocp_socket_service_base.ipp b/third/asio/detail/impl/win_iocp_socket_service_base.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_iocp_socket_service_base.ipp rename to third/asio/detail/impl/win_iocp_socket_service_base.ipp diff --git a/sdk/third/asio/detail/impl/win_mutex.ipp b/third/asio/detail/impl/win_mutex.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_mutex.ipp rename to third/asio/detail/impl/win_mutex.ipp diff --git a/sdk/third/asio/detail/impl/win_object_handle_service.ipp b/third/asio/detail/impl/win_object_handle_service.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_object_handle_service.ipp rename to third/asio/detail/impl/win_object_handle_service.ipp diff --git a/sdk/third/asio/detail/impl/win_static_mutex.ipp b/third/asio/detail/impl/win_static_mutex.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_static_mutex.ipp rename to third/asio/detail/impl/win_static_mutex.ipp diff --git a/sdk/third/asio/detail/impl/win_thread.ipp b/third/asio/detail/impl/win_thread.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_thread.ipp rename to third/asio/detail/impl/win_thread.ipp diff --git a/sdk/third/asio/detail/impl/win_tss_ptr.ipp b/third/asio/detail/impl/win_tss_ptr.ipp similarity index 100% rename from sdk/third/asio/detail/impl/win_tss_ptr.ipp rename to third/asio/detail/impl/win_tss_ptr.ipp diff --git a/sdk/third/asio/detail/impl/winrt_ssocket_service_base.ipp b/third/asio/detail/impl/winrt_ssocket_service_base.ipp similarity index 100% rename from sdk/third/asio/detail/impl/winrt_ssocket_service_base.ipp rename to third/asio/detail/impl/winrt_ssocket_service_base.ipp diff --git a/sdk/third/asio/detail/impl/winrt_timer_scheduler.hpp b/third/asio/detail/impl/winrt_timer_scheduler.hpp similarity index 100% rename from sdk/third/asio/detail/impl/winrt_timer_scheduler.hpp rename to third/asio/detail/impl/winrt_timer_scheduler.hpp diff --git a/sdk/third/asio/detail/impl/winrt_timer_scheduler.ipp b/third/asio/detail/impl/winrt_timer_scheduler.ipp similarity index 100% rename from sdk/third/asio/detail/impl/winrt_timer_scheduler.ipp rename to third/asio/detail/impl/winrt_timer_scheduler.ipp diff --git a/sdk/third/asio/detail/impl/winsock_init.ipp b/third/asio/detail/impl/winsock_init.ipp similarity index 100% rename from sdk/third/asio/detail/impl/winsock_init.ipp rename to third/asio/detail/impl/winsock_init.ipp diff --git a/sdk/third/asio/detail/io_control.hpp b/third/asio/detail/io_control.hpp similarity index 100% rename from sdk/third/asio/detail/io_control.hpp rename to third/asio/detail/io_control.hpp diff --git a/sdk/third/asio/detail/io_object_impl.hpp b/third/asio/detail/io_object_impl.hpp similarity index 100% rename from sdk/third/asio/detail/io_object_impl.hpp rename to third/asio/detail/io_object_impl.hpp diff --git a/sdk/third/asio/detail/io_uring_descriptor_read_at_op.hpp b/third/asio/detail/io_uring_descriptor_read_at_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_descriptor_read_at_op.hpp rename to third/asio/detail/io_uring_descriptor_read_at_op.hpp diff --git a/sdk/third/asio/detail/io_uring_descriptor_read_op.hpp b/third/asio/detail/io_uring_descriptor_read_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_descriptor_read_op.hpp rename to third/asio/detail/io_uring_descriptor_read_op.hpp diff --git a/sdk/third/asio/detail/io_uring_descriptor_service.hpp b/third/asio/detail/io_uring_descriptor_service.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_descriptor_service.hpp rename to third/asio/detail/io_uring_descriptor_service.hpp diff --git a/sdk/third/asio/detail/io_uring_descriptor_write_at_op.hpp b/third/asio/detail/io_uring_descriptor_write_at_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_descriptor_write_at_op.hpp rename to third/asio/detail/io_uring_descriptor_write_at_op.hpp diff --git a/sdk/third/asio/detail/io_uring_descriptor_write_op.hpp b/third/asio/detail/io_uring_descriptor_write_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_descriptor_write_op.hpp rename to third/asio/detail/io_uring_descriptor_write_op.hpp diff --git a/sdk/third/asio/detail/io_uring_file_service.hpp b/third/asio/detail/io_uring_file_service.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_file_service.hpp rename to third/asio/detail/io_uring_file_service.hpp diff --git a/sdk/third/asio/detail/io_uring_null_buffers_op.hpp b/third/asio/detail/io_uring_null_buffers_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_null_buffers_op.hpp rename to third/asio/detail/io_uring_null_buffers_op.hpp diff --git a/sdk/third/asio/detail/io_uring_operation.hpp b/third/asio/detail/io_uring_operation.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_operation.hpp rename to third/asio/detail/io_uring_operation.hpp diff --git a/sdk/third/asio/detail/io_uring_service.hpp b/third/asio/detail/io_uring_service.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_service.hpp rename to third/asio/detail/io_uring_service.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_accept_op.hpp b/third/asio/detail/io_uring_socket_accept_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_accept_op.hpp rename to third/asio/detail/io_uring_socket_accept_op.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_connect_op.hpp b/third/asio/detail/io_uring_socket_connect_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_connect_op.hpp rename to third/asio/detail/io_uring_socket_connect_op.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_recv_op.hpp b/third/asio/detail/io_uring_socket_recv_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_recv_op.hpp rename to third/asio/detail/io_uring_socket_recv_op.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_recvfrom_op.hpp b/third/asio/detail/io_uring_socket_recvfrom_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_recvfrom_op.hpp rename to third/asio/detail/io_uring_socket_recvfrom_op.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_recvmsg_op.hpp b/third/asio/detail/io_uring_socket_recvmsg_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_recvmsg_op.hpp rename to third/asio/detail/io_uring_socket_recvmsg_op.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_send_op.hpp b/third/asio/detail/io_uring_socket_send_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_send_op.hpp rename to third/asio/detail/io_uring_socket_send_op.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_sendto_op.hpp b/third/asio/detail/io_uring_socket_sendto_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_sendto_op.hpp rename to third/asio/detail/io_uring_socket_sendto_op.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_service.hpp b/third/asio/detail/io_uring_socket_service.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_service.hpp rename to third/asio/detail/io_uring_socket_service.hpp diff --git a/sdk/third/asio/detail/io_uring_socket_service_base.hpp b/third/asio/detail/io_uring_socket_service_base.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_socket_service_base.hpp rename to third/asio/detail/io_uring_socket_service_base.hpp diff --git a/sdk/third/asio/detail/io_uring_wait_op.hpp b/third/asio/detail/io_uring_wait_op.hpp similarity index 100% rename from sdk/third/asio/detail/io_uring_wait_op.hpp rename to third/asio/detail/io_uring_wait_op.hpp diff --git a/sdk/third/asio/detail/is_buffer_sequence.hpp b/third/asio/detail/is_buffer_sequence.hpp similarity index 100% rename from sdk/third/asio/detail/is_buffer_sequence.hpp rename to third/asio/detail/is_buffer_sequence.hpp diff --git a/sdk/third/asio/detail/is_executor.hpp b/third/asio/detail/is_executor.hpp similarity index 100% rename from sdk/third/asio/detail/is_executor.hpp rename to third/asio/detail/is_executor.hpp diff --git a/sdk/third/asio/detail/keyword_tss_ptr.hpp b/third/asio/detail/keyword_tss_ptr.hpp similarity index 100% rename from sdk/third/asio/detail/keyword_tss_ptr.hpp rename to third/asio/detail/keyword_tss_ptr.hpp diff --git a/sdk/third/asio/detail/kqueue_reactor.hpp b/third/asio/detail/kqueue_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/kqueue_reactor.hpp rename to third/asio/detail/kqueue_reactor.hpp diff --git a/sdk/third/asio/detail/limits.hpp b/third/asio/detail/limits.hpp similarity index 100% rename from sdk/third/asio/detail/limits.hpp rename to third/asio/detail/limits.hpp diff --git a/sdk/third/asio/detail/local_free_on_block_exit.hpp b/third/asio/detail/local_free_on_block_exit.hpp similarity index 100% rename from sdk/third/asio/detail/local_free_on_block_exit.hpp rename to third/asio/detail/local_free_on_block_exit.hpp diff --git a/sdk/third/asio/detail/macos_fenced_block.hpp b/third/asio/detail/macos_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/macos_fenced_block.hpp rename to third/asio/detail/macos_fenced_block.hpp diff --git a/sdk/third/asio/detail/memory.hpp b/third/asio/detail/memory.hpp similarity index 100% rename from sdk/third/asio/detail/memory.hpp rename to third/asio/detail/memory.hpp diff --git a/sdk/third/asio/detail/mutex.hpp b/third/asio/detail/mutex.hpp similarity index 100% rename from sdk/third/asio/detail/mutex.hpp rename to third/asio/detail/mutex.hpp diff --git a/sdk/third/asio/detail/non_const_lvalue.hpp b/third/asio/detail/non_const_lvalue.hpp similarity index 100% rename from sdk/third/asio/detail/non_const_lvalue.hpp rename to third/asio/detail/non_const_lvalue.hpp diff --git a/sdk/third/asio/detail/noncopyable.hpp b/third/asio/detail/noncopyable.hpp similarity index 100% rename from sdk/third/asio/detail/noncopyable.hpp rename to third/asio/detail/noncopyable.hpp diff --git a/sdk/third/asio/detail/null_event.hpp b/third/asio/detail/null_event.hpp similarity index 100% rename from sdk/third/asio/detail/null_event.hpp rename to third/asio/detail/null_event.hpp diff --git a/sdk/third/asio/detail/null_fenced_block.hpp b/third/asio/detail/null_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/null_fenced_block.hpp rename to third/asio/detail/null_fenced_block.hpp diff --git a/sdk/third/asio/detail/null_global.hpp b/third/asio/detail/null_global.hpp similarity index 100% rename from sdk/third/asio/detail/null_global.hpp rename to third/asio/detail/null_global.hpp diff --git a/sdk/third/asio/detail/null_mutex.hpp b/third/asio/detail/null_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/null_mutex.hpp rename to third/asio/detail/null_mutex.hpp diff --git a/sdk/third/asio/detail/null_reactor.hpp b/third/asio/detail/null_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/null_reactor.hpp rename to third/asio/detail/null_reactor.hpp diff --git a/sdk/third/asio/detail/null_signal_blocker.hpp b/third/asio/detail/null_signal_blocker.hpp similarity index 100% rename from sdk/third/asio/detail/null_signal_blocker.hpp rename to third/asio/detail/null_signal_blocker.hpp diff --git a/sdk/third/asio/detail/null_socket_service.hpp b/third/asio/detail/null_socket_service.hpp similarity index 100% rename from sdk/third/asio/detail/null_socket_service.hpp rename to third/asio/detail/null_socket_service.hpp diff --git a/sdk/third/asio/detail/null_static_mutex.hpp b/third/asio/detail/null_static_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/null_static_mutex.hpp rename to third/asio/detail/null_static_mutex.hpp diff --git a/sdk/third/asio/detail/null_thread.hpp b/third/asio/detail/null_thread.hpp similarity index 100% rename from sdk/third/asio/detail/null_thread.hpp rename to third/asio/detail/null_thread.hpp diff --git a/sdk/third/asio/detail/null_tss_ptr.hpp b/third/asio/detail/null_tss_ptr.hpp similarity index 100% rename from sdk/third/asio/detail/null_tss_ptr.hpp rename to third/asio/detail/null_tss_ptr.hpp diff --git a/sdk/third/asio/detail/object_pool.hpp b/third/asio/detail/object_pool.hpp similarity index 100% rename from sdk/third/asio/detail/object_pool.hpp rename to third/asio/detail/object_pool.hpp diff --git a/sdk/third/asio/detail/old_win_sdk_compat.hpp b/third/asio/detail/old_win_sdk_compat.hpp similarity index 100% rename from sdk/third/asio/detail/old_win_sdk_compat.hpp rename to third/asio/detail/old_win_sdk_compat.hpp diff --git a/sdk/third/asio/detail/op_queue.hpp b/third/asio/detail/op_queue.hpp similarity index 100% rename from sdk/third/asio/detail/op_queue.hpp rename to third/asio/detail/op_queue.hpp diff --git a/sdk/third/asio/detail/operation.hpp b/third/asio/detail/operation.hpp similarity index 100% rename from sdk/third/asio/detail/operation.hpp rename to third/asio/detail/operation.hpp diff --git a/sdk/third/asio/detail/pipe_select_interrupter.hpp b/third/asio/detail/pipe_select_interrupter.hpp similarity index 100% rename from sdk/third/asio/detail/pipe_select_interrupter.hpp rename to third/asio/detail/pipe_select_interrupter.hpp diff --git a/sdk/third/asio/detail/pop_options.hpp b/third/asio/detail/pop_options.hpp similarity index 100% rename from sdk/third/asio/detail/pop_options.hpp rename to third/asio/detail/pop_options.hpp diff --git a/sdk/third/asio/detail/posix_event.hpp b/third/asio/detail/posix_event.hpp similarity index 100% rename from sdk/third/asio/detail/posix_event.hpp rename to third/asio/detail/posix_event.hpp diff --git a/sdk/third/asio/detail/posix_fd_set_adapter.hpp b/third/asio/detail/posix_fd_set_adapter.hpp similarity index 100% rename from sdk/third/asio/detail/posix_fd_set_adapter.hpp rename to third/asio/detail/posix_fd_set_adapter.hpp diff --git a/sdk/third/asio/detail/posix_global.hpp b/third/asio/detail/posix_global.hpp similarity index 100% rename from sdk/third/asio/detail/posix_global.hpp rename to third/asio/detail/posix_global.hpp diff --git a/sdk/third/asio/detail/posix_mutex.hpp b/third/asio/detail/posix_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/posix_mutex.hpp rename to third/asio/detail/posix_mutex.hpp diff --git a/sdk/third/asio/detail/posix_serial_port_service.hpp b/third/asio/detail/posix_serial_port_service.hpp similarity index 100% rename from sdk/third/asio/detail/posix_serial_port_service.hpp rename to third/asio/detail/posix_serial_port_service.hpp diff --git a/sdk/third/asio/detail/posix_signal_blocker.hpp b/third/asio/detail/posix_signal_blocker.hpp similarity index 100% rename from sdk/third/asio/detail/posix_signal_blocker.hpp rename to third/asio/detail/posix_signal_blocker.hpp diff --git a/sdk/third/asio/detail/posix_static_mutex.hpp b/third/asio/detail/posix_static_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/posix_static_mutex.hpp rename to third/asio/detail/posix_static_mutex.hpp diff --git a/sdk/third/asio/detail/posix_thread.hpp b/third/asio/detail/posix_thread.hpp similarity index 100% rename from sdk/third/asio/detail/posix_thread.hpp rename to third/asio/detail/posix_thread.hpp diff --git a/sdk/third/asio/detail/posix_tss_ptr.hpp b/third/asio/detail/posix_tss_ptr.hpp similarity index 100% rename from sdk/third/asio/detail/posix_tss_ptr.hpp rename to third/asio/detail/posix_tss_ptr.hpp diff --git a/sdk/third/asio/detail/push_options.hpp b/third/asio/detail/push_options.hpp similarity index 100% rename from sdk/third/asio/detail/push_options.hpp rename to third/asio/detail/push_options.hpp diff --git a/sdk/third/asio/detail/reactive_descriptor_service.hpp b/third/asio/detail/reactive_descriptor_service.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_descriptor_service.hpp rename to third/asio/detail/reactive_descriptor_service.hpp diff --git a/sdk/third/asio/detail/reactive_null_buffers_op.hpp b/third/asio/detail/reactive_null_buffers_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_null_buffers_op.hpp rename to third/asio/detail/reactive_null_buffers_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_accept_op.hpp b/third/asio/detail/reactive_socket_accept_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_accept_op.hpp rename to third/asio/detail/reactive_socket_accept_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_connect_op.hpp b/third/asio/detail/reactive_socket_connect_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_connect_op.hpp rename to third/asio/detail/reactive_socket_connect_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_recv_op.hpp b/third/asio/detail/reactive_socket_recv_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_recv_op.hpp rename to third/asio/detail/reactive_socket_recv_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_recvfrom_op.hpp b/third/asio/detail/reactive_socket_recvfrom_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_recvfrom_op.hpp rename to third/asio/detail/reactive_socket_recvfrom_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_recvmsg_op.hpp b/third/asio/detail/reactive_socket_recvmsg_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_recvmsg_op.hpp rename to third/asio/detail/reactive_socket_recvmsg_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_send_op.hpp b/third/asio/detail/reactive_socket_send_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_send_op.hpp rename to third/asio/detail/reactive_socket_send_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_sendto_op.hpp b/third/asio/detail/reactive_socket_sendto_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_sendto_op.hpp rename to third/asio/detail/reactive_socket_sendto_op.hpp diff --git a/sdk/third/asio/detail/reactive_socket_service.hpp b/third/asio/detail/reactive_socket_service.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_service.hpp rename to third/asio/detail/reactive_socket_service.hpp diff --git a/sdk/third/asio/detail/reactive_socket_service_base.hpp b/third/asio/detail/reactive_socket_service_base.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_socket_service_base.hpp rename to third/asio/detail/reactive_socket_service_base.hpp diff --git a/sdk/third/asio/detail/reactive_wait_op.hpp b/third/asio/detail/reactive_wait_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactive_wait_op.hpp rename to third/asio/detail/reactive_wait_op.hpp diff --git a/sdk/third/asio/detail/reactor.hpp b/third/asio/detail/reactor.hpp similarity index 100% rename from sdk/third/asio/detail/reactor.hpp rename to third/asio/detail/reactor.hpp diff --git a/sdk/third/asio/detail/reactor_op.hpp b/third/asio/detail/reactor_op.hpp similarity index 100% rename from sdk/third/asio/detail/reactor_op.hpp rename to third/asio/detail/reactor_op.hpp diff --git a/sdk/third/asio/detail/reactor_op_queue.hpp b/third/asio/detail/reactor_op_queue.hpp similarity index 100% rename from sdk/third/asio/detail/reactor_op_queue.hpp rename to third/asio/detail/reactor_op_queue.hpp diff --git a/sdk/third/asio/detail/recycling_allocator.hpp b/third/asio/detail/recycling_allocator.hpp similarity index 100% rename from sdk/third/asio/detail/recycling_allocator.hpp rename to third/asio/detail/recycling_allocator.hpp diff --git a/sdk/third/asio/detail/regex_fwd.hpp b/third/asio/detail/regex_fwd.hpp similarity index 100% rename from sdk/third/asio/detail/regex_fwd.hpp rename to third/asio/detail/regex_fwd.hpp diff --git a/sdk/third/asio/detail/resolve_endpoint_op.hpp b/third/asio/detail/resolve_endpoint_op.hpp similarity index 100% rename from sdk/third/asio/detail/resolve_endpoint_op.hpp rename to third/asio/detail/resolve_endpoint_op.hpp diff --git a/sdk/third/asio/detail/resolve_op.hpp b/third/asio/detail/resolve_op.hpp similarity index 100% rename from sdk/third/asio/detail/resolve_op.hpp rename to third/asio/detail/resolve_op.hpp diff --git a/sdk/third/asio/detail/resolve_query_op.hpp b/third/asio/detail/resolve_query_op.hpp similarity index 100% rename from sdk/third/asio/detail/resolve_query_op.hpp rename to third/asio/detail/resolve_query_op.hpp diff --git a/sdk/third/asio/detail/resolver_service.hpp b/third/asio/detail/resolver_service.hpp similarity index 100% rename from sdk/third/asio/detail/resolver_service.hpp rename to third/asio/detail/resolver_service.hpp diff --git a/sdk/third/asio/detail/resolver_service_base.hpp b/third/asio/detail/resolver_service_base.hpp similarity index 100% rename from sdk/third/asio/detail/resolver_service_base.hpp rename to third/asio/detail/resolver_service_base.hpp diff --git a/sdk/third/asio/detail/scheduler.hpp b/third/asio/detail/scheduler.hpp similarity index 100% rename from sdk/third/asio/detail/scheduler.hpp rename to third/asio/detail/scheduler.hpp diff --git a/sdk/third/asio/detail/scheduler_operation.hpp b/third/asio/detail/scheduler_operation.hpp similarity index 100% rename from sdk/third/asio/detail/scheduler_operation.hpp rename to third/asio/detail/scheduler_operation.hpp diff --git a/sdk/third/asio/detail/scheduler_task.hpp b/third/asio/detail/scheduler_task.hpp similarity index 100% rename from sdk/third/asio/detail/scheduler_task.hpp rename to third/asio/detail/scheduler_task.hpp diff --git a/sdk/third/asio/detail/scheduler_thread_info.hpp b/third/asio/detail/scheduler_thread_info.hpp similarity index 100% rename from sdk/third/asio/detail/scheduler_thread_info.hpp rename to third/asio/detail/scheduler_thread_info.hpp diff --git a/sdk/third/asio/detail/scoped_lock.hpp b/third/asio/detail/scoped_lock.hpp similarity index 100% rename from sdk/third/asio/detail/scoped_lock.hpp rename to third/asio/detail/scoped_lock.hpp diff --git a/sdk/third/asio/detail/scoped_ptr.hpp b/third/asio/detail/scoped_ptr.hpp similarity index 100% rename from sdk/third/asio/detail/scoped_ptr.hpp rename to third/asio/detail/scoped_ptr.hpp diff --git a/sdk/third/asio/detail/select_interrupter.hpp b/third/asio/detail/select_interrupter.hpp similarity index 100% rename from sdk/third/asio/detail/select_interrupter.hpp rename to third/asio/detail/select_interrupter.hpp diff --git a/sdk/third/asio/detail/select_reactor.hpp b/third/asio/detail/select_reactor.hpp similarity index 100% rename from sdk/third/asio/detail/select_reactor.hpp rename to third/asio/detail/select_reactor.hpp diff --git a/sdk/third/asio/detail/service_registry.hpp b/third/asio/detail/service_registry.hpp similarity index 100% rename from sdk/third/asio/detail/service_registry.hpp rename to third/asio/detail/service_registry.hpp diff --git a/sdk/third/asio/detail/signal_blocker.hpp b/third/asio/detail/signal_blocker.hpp similarity index 100% rename from sdk/third/asio/detail/signal_blocker.hpp rename to third/asio/detail/signal_blocker.hpp diff --git a/sdk/third/asio/detail/signal_handler.hpp b/third/asio/detail/signal_handler.hpp similarity index 100% rename from sdk/third/asio/detail/signal_handler.hpp rename to third/asio/detail/signal_handler.hpp diff --git a/sdk/third/asio/detail/signal_init.hpp b/third/asio/detail/signal_init.hpp similarity index 100% rename from sdk/third/asio/detail/signal_init.hpp rename to third/asio/detail/signal_init.hpp diff --git a/sdk/third/asio/detail/signal_op.hpp b/third/asio/detail/signal_op.hpp similarity index 100% rename from sdk/third/asio/detail/signal_op.hpp rename to third/asio/detail/signal_op.hpp diff --git a/sdk/third/asio/detail/signal_set_service.hpp b/third/asio/detail/signal_set_service.hpp similarity index 100% rename from sdk/third/asio/detail/signal_set_service.hpp rename to third/asio/detail/signal_set_service.hpp diff --git a/sdk/third/asio/detail/socket_holder.hpp b/third/asio/detail/socket_holder.hpp similarity index 100% rename from sdk/third/asio/detail/socket_holder.hpp rename to third/asio/detail/socket_holder.hpp diff --git a/sdk/third/asio/detail/socket_ops.hpp b/third/asio/detail/socket_ops.hpp similarity index 100% rename from sdk/third/asio/detail/socket_ops.hpp rename to third/asio/detail/socket_ops.hpp diff --git a/sdk/third/asio/detail/socket_option.hpp b/third/asio/detail/socket_option.hpp similarity index 100% rename from sdk/third/asio/detail/socket_option.hpp rename to third/asio/detail/socket_option.hpp diff --git a/sdk/third/asio/detail/socket_select_interrupter.hpp b/third/asio/detail/socket_select_interrupter.hpp similarity index 100% rename from sdk/third/asio/detail/socket_select_interrupter.hpp rename to third/asio/detail/socket_select_interrupter.hpp diff --git a/sdk/third/asio/detail/socket_types.hpp b/third/asio/detail/socket_types.hpp similarity index 100% rename from sdk/third/asio/detail/socket_types.hpp rename to third/asio/detail/socket_types.hpp diff --git a/sdk/third/asio/detail/solaris_fenced_block.hpp b/third/asio/detail/solaris_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/solaris_fenced_block.hpp rename to third/asio/detail/solaris_fenced_block.hpp diff --git a/sdk/third/asio/detail/source_location.hpp b/third/asio/detail/source_location.hpp similarity index 100% rename from sdk/third/asio/detail/source_location.hpp rename to third/asio/detail/source_location.hpp diff --git a/sdk/third/asio/detail/static_mutex.hpp b/third/asio/detail/static_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/static_mutex.hpp rename to third/asio/detail/static_mutex.hpp diff --git a/sdk/third/asio/detail/std_event.hpp b/third/asio/detail/std_event.hpp similarity index 100% rename from sdk/third/asio/detail/std_event.hpp rename to third/asio/detail/std_event.hpp diff --git a/sdk/third/asio/detail/std_fenced_block.hpp b/third/asio/detail/std_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/std_fenced_block.hpp rename to third/asio/detail/std_fenced_block.hpp diff --git a/sdk/third/asio/detail/std_global.hpp b/third/asio/detail/std_global.hpp similarity index 100% rename from sdk/third/asio/detail/std_global.hpp rename to third/asio/detail/std_global.hpp diff --git a/sdk/third/asio/detail/std_mutex.hpp b/third/asio/detail/std_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/std_mutex.hpp rename to third/asio/detail/std_mutex.hpp diff --git a/sdk/third/asio/detail/std_static_mutex.hpp b/third/asio/detail/std_static_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/std_static_mutex.hpp rename to third/asio/detail/std_static_mutex.hpp diff --git a/sdk/third/asio/detail/std_thread.hpp b/third/asio/detail/std_thread.hpp similarity index 100% rename from sdk/third/asio/detail/std_thread.hpp rename to third/asio/detail/std_thread.hpp diff --git a/sdk/third/asio/detail/strand_executor_service.hpp b/third/asio/detail/strand_executor_service.hpp similarity index 100% rename from sdk/third/asio/detail/strand_executor_service.hpp rename to third/asio/detail/strand_executor_service.hpp diff --git a/sdk/third/asio/detail/strand_service.hpp b/third/asio/detail/strand_service.hpp similarity index 100% rename from sdk/third/asio/detail/strand_service.hpp rename to third/asio/detail/strand_service.hpp diff --git a/sdk/third/asio/detail/string_view.hpp b/third/asio/detail/string_view.hpp similarity index 100% rename from sdk/third/asio/detail/string_view.hpp rename to third/asio/detail/string_view.hpp diff --git a/sdk/third/asio/detail/thread.hpp b/third/asio/detail/thread.hpp similarity index 100% rename from sdk/third/asio/detail/thread.hpp rename to third/asio/detail/thread.hpp diff --git a/sdk/third/asio/detail/thread_context.hpp b/third/asio/detail/thread_context.hpp similarity index 100% rename from sdk/third/asio/detail/thread_context.hpp rename to third/asio/detail/thread_context.hpp diff --git a/sdk/third/asio/detail/thread_group.hpp b/third/asio/detail/thread_group.hpp similarity index 100% rename from sdk/third/asio/detail/thread_group.hpp rename to third/asio/detail/thread_group.hpp diff --git a/sdk/third/asio/detail/thread_info_base.hpp b/third/asio/detail/thread_info_base.hpp similarity index 100% rename from sdk/third/asio/detail/thread_info_base.hpp rename to third/asio/detail/thread_info_base.hpp diff --git a/sdk/third/asio/detail/throw_error.hpp b/third/asio/detail/throw_error.hpp similarity index 100% rename from sdk/third/asio/detail/throw_error.hpp rename to third/asio/detail/throw_error.hpp diff --git a/sdk/third/asio/detail/throw_exception.hpp b/third/asio/detail/throw_exception.hpp similarity index 100% rename from sdk/third/asio/detail/throw_exception.hpp rename to third/asio/detail/throw_exception.hpp diff --git a/sdk/third/asio/detail/timer_queue.hpp b/third/asio/detail/timer_queue.hpp similarity index 100% rename from sdk/third/asio/detail/timer_queue.hpp rename to third/asio/detail/timer_queue.hpp diff --git a/sdk/third/asio/detail/timer_queue_base.hpp b/third/asio/detail/timer_queue_base.hpp similarity index 100% rename from sdk/third/asio/detail/timer_queue_base.hpp rename to third/asio/detail/timer_queue_base.hpp diff --git a/sdk/third/asio/detail/timer_queue_ptime.hpp b/third/asio/detail/timer_queue_ptime.hpp similarity index 100% rename from sdk/third/asio/detail/timer_queue_ptime.hpp rename to third/asio/detail/timer_queue_ptime.hpp diff --git a/sdk/third/asio/detail/timer_queue_set.hpp b/third/asio/detail/timer_queue_set.hpp similarity index 100% rename from sdk/third/asio/detail/timer_queue_set.hpp rename to third/asio/detail/timer_queue_set.hpp diff --git a/sdk/third/asio/detail/timer_scheduler.hpp b/third/asio/detail/timer_scheduler.hpp similarity index 100% rename from sdk/third/asio/detail/timer_scheduler.hpp rename to third/asio/detail/timer_scheduler.hpp diff --git a/sdk/third/asio/detail/timer_scheduler_fwd.hpp b/third/asio/detail/timer_scheduler_fwd.hpp similarity index 100% rename from sdk/third/asio/detail/timer_scheduler_fwd.hpp rename to third/asio/detail/timer_scheduler_fwd.hpp diff --git a/sdk/third/asio/detail/tss_ptr.hpp b/third/asio/detail/tss_ptr.hpp similarity index 100% rename from sdk/third/asio/detail/tss_ptr.hpp rename to third/asio/detail/tss_ptr.hpp diff --git a/sdk/third/asio/detail/type_traits.hpp b/third/asio/detail/type_traits.hpp similarity index 100% rename from sdk/third/asio/detail/type_traits.hpp rename to third/asio/detail/type_traits.hpp diff --git a/sdk/third/asio/detail/utility.hpp b/third/asio/detail/utility.hpp similarity index 100% rename from sdk/third/asio/detail/utility.hpp rename to third/asio/detail/utility.hpp diff --git a/sdk/third/asio/detail/variadic_templates.hpp b/third/asio/detail/variadic_templates.hpp similarity index 100% rename from sdk/third/asio/detail/variadic_templates.hpp rename to third/asio/detail/variadic_templates.hpp diff --git a/sdk/third/asio/detail/wait_handler.hpp b/third/asio/detail/wait_handler.hpp similarity index 100% rename from sdk/third/asio/detail/wait_handler.hpp rename to third/asio/detail/wait_handler.hpp diff --git a/sdk/third/asio/detail/wait_op.hpp b/third/asio/detail/wait_op.hpp similarity index 100% rename from sdk/third/asio/detail/wait_op.hpp rename to third/asio/detail/wait_op.hpp diff --git a/sdk/third/asio/detail/win_event.hpp b/third/asio/detail/win_event.hpp similarity index 100% rename from sdk/third/asio/detail/win_event.hpp rename to third/asio/detail/win_event.hpp diff --git a/sdk/third/asio/detail/win_fd_set_adapter.hpp b/third/asio/detail/win_fd_set_adapter.hpp similarity index 100% rename from sdk/third/asio/detail/win_fd_set_adapter.hpp rename to third/asio/detail/win_fd_set_adapter.hpp diff --git a/sdk/third/asio/detail/win_fenced_block.hpp b/third/asio/detail/win_fenced_block.hpp similarity index 100% rename from sdk/third/asio/detail/win_fenced_block.hpp rename to third/asio/detail/win_fenced_block.hpp diff --git a/sdk/third/asio/detail/win_global.hpp b/third/asio/detail/win_global.hpp similarity index 100% rename from sdk/third/asio/detail/win_global.hpp rename to third/asio/detail/win_global.hpp diff --git a/sdk/third/asio/detail/win_iocp_file_service.hpp b/third/asio/detail/win_iocp_file_service.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_file_service.hpp rename to third/asio/detail/win_iocp_file_service.hpp diff --git a/sdk/third/asio/detail/win_iocp_handle_read_op.hpp b/third/asio/detail/win_iocp_handle_read_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_handle_read_op.hpp rename to third/asio/detail/win_iocp_handle_read_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_handle_service.hpp b/third/asio/detail/win_iocp_handle_service.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_handle_service.hpp rename to third/asio/detail/win_iocp_handle_service.hpp diff --git a/sdk/third/asio/detail/win_iocp_handle_write_op.hpp b/third/asio/detail/win_iocp_handle_write_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_handle_write_op.hpp rename to third/asio/detail/win_iocp_handle_write_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_io_context.hpp b/third/asio/detail/win_iocp_io_context.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_io_context.hpp rename to third/asio/detail/win_iocp_io_context.hpp diff --git a/sdk/third/asio/detail/win_iocp_null_buffers_op.hpp b/third/asio/detail/win_iocp_null_buffers_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_null_buffers_op.hpp rename to third/asio/detail/win_iocp_null_buffers_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_operation.hpp b/third/asio/detail/win_iocp_operation.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_operation.hpp rename to third/asio/detail/win_iocp_operation.hpp diff --git a/sdk/third/asio/detail/win_iocp_overlapped_op.hpp b/third/asio/detail/win_iocp_overlapped_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_overlapped_op.hpp rename to third/asio/detail/win_iocp_overlapped_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_overlapped_ptr.hpp b/third/asio/detail/win_iocp_overlapped_ptr.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_overlapped_ptr.hpp rename to third/asio/detail/win_iocp_overlapped_ptr.hpp diff --git a/sdk/third/asio/detail/win_iocp_serial_port_service.hpp b/third/asio/detail/win_iocp_serial_port_service.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_serial_port_service.hpp rename to third/asio/detail/win_iocp_serial_port_service.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_accept_op.hpp b/third/asio/detail/win_iocp_socket_accept_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_accept_op.hpp rename to third/asio/detail/win_iocp_socket_accept_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_connect_op.hpp b/third/asio/detail/win_iocp_socket_connect_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_connect_op.hpp rename to third/asio/detail/win_iocp_socket_connect_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_recv_op.hpp b/third/asio/detail/win_iocp_socket_recv_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_recv_op.hpp rename to third/asio/detail/win_iocp_socket_recv_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_recvfrom_op.hpp b/third/asio/detail/win_iocp_socket_recvfrom_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_recvfrom_op.hpp rename to third/asio/detail/win_iocp_socket_recvfrom_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_recvmsg_op.hpp b/third/asio/detail/win_iocp_socket_recvmsg_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_recvmsg_op.hpp rename to third/asio/detail/win_iocp_socket_recvmsg_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_send_op.hpp b/third/asio/detail/win_iocp_socket_send_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_send_op.hpp rename to third/asio/detail/win_iocp_socket_send_op.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_service.hpp b/third/asio/detail/win_iocp_socket_service.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_service.hpp rename to third/asio/detail/win_iocp_socket_service.hpp diff --git a/sdk/third/asio/detail/win_iocp_socket_service_base.hpp b/third/asio/detail/win_iocp_socket_service_base.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_socket_service_base.hpp rename to third/asio/detail/win_iocp_socket_service_base.hpp diff --git a/sdk/third/asio/detail/win_iocp_thread_info.hpp b/third/asio/detail/win_iocp_thread_info.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_thread_info.hpp rename to third/asio/detail/win_iocp_thread_info.hpp diff --git a/sdk/third/asio/detail/win_iocp_wait_op.hpp b/third/asio/detail/win_iocp_wait_op.hpp similarity index 100% rename from sdk/third/asio/detail/win_iocp_wait_op.hpp rename to third/asio/detail/win_iocp_wait_op.hpp diff --git a/sdk/third/asio/detail/win_mutex.hpp b/third/asio/detail/win_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/win_mutex.hpp rename to third/asio/detail/win_mutex.hpp diff --git a/sdk/third/asio/detail/win_object_handle_service.hpp b/third/asio/detail/win_object_handle_service.hpp similarity index 100% rename from sdk/third/asio/detail/win_object_handle_service.hpp rename to third/asio/detail/win_object_handle_service.hpp diff --git a/sdk/third/asio/detail/win_static_mutex.hpp b/third/asio/detail/win_static_mutex.hpp similarity index 100% rename from sdk/third/asio/detail/win_static_mutex.hpp rename to third/asio/detail/win_static_mutex.hpp diff --git a/sdk/third/asio/detail/win_thread.hpp b/third/asio/detail/win_thread.hpp similarity index 100% rename from sdk/third/asio/detail/win_thread.hpp rename to third/asio/detail/win_thread.hpp diff --git a/sdk/third/asio/detail/win_tss_ptr.hpp b/third/asio/detail/win_tss_ptr.hpp similarity index 100% rename from sdk/third/asio/detail/win_tss_ptr.hpp rename to third/asio/detail/win_tss_ptr.hpp diff --git a/sdk/third/asio/detail/winapp_thread.hpp b/third/asio/detail/winapp_thread.hpp similarity index 100% rename from sdk/third/asio/detail/winapp_thread.hpp rename to third/asio/detail/winapp_thread.hpp diff --git a/sdk/third/asio/detail/wince_thread.hpp b/third/asio/detail/wince_thread.hpp similarity index 100% rename from sdk/third/asio/detail/wince_thread.hpp rename to third/asio/detail/wince_thread.hpp diff --git a/sdk/third/asio/detail/winrt_async_manager.hpp b/third/asio/detail/winrt_async_manager.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_async_manager.hpp rename to third/asio/detail/winrt_async_manager.hpp diff --git a/sdk/third/asio/detail/winrt_async_op.hpp b/third/asio/detail/winrt_async_op.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_async_op.hpp rename to third/asio/detail/winrt_async_op.hpp diff --git a/sdk/third/asio/detail/winrt_resolve_op.hpp b/third/asio/detail/winrt_resolve_op.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_resolve_op.hpp rename to third/asio/detail/winrt_resolve_op.hpp diff --git a/sdk/third/asio/detail/winrt_resolver_service.hpp b/third/asio/detail/winrt_resolver_service.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_resolver_service.hpp rename to third/asio/detail/winrt_resolver_service.hpp diff --git a/sdk/third/asio/detail/winrt_socket_connect_op.hpp b/third/asio/detail/winrt_socket_connect_op.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_socket_connect_op.hpp rename to third/asio/detail/winrt_socket_connect_op.hpp diff --git a/sdk/third/asio/detail/winrt_socket_recv_op.hpp b/third/asio/detail/winrt_socket_recv_op.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_socket_recv_op.hpp rename to third/asio/detail/winrt_socket_recv_op.hpp diff --git a/sdk/third/asio/detail/winrt_socket_send_op.hpp b/third/asio/detail/winrt_socket_send_op.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_socket_send_op.hpp rename to third/asio/detail/winrt_socket_send_op.hpp diff --git a/sdk/third/asio/detail/winrt_ssocket_service.hpp b/third/asio/detail/winrt_ssocket_service.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_ssocket_service.hpp rename to third/asio/detail/winrt_ssocket_service.hpp diff --git a/sdk/third/asio/detail/winrt_ssocket_service_base.hpp b/third/asio/detail/winrt_ssocket_service_base.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_ssocket_service_base.hpp rename to third/asio/detail/winrt_ssocket_service_base.hpp diff --git a/sdk/third/asio/detail/winrt_timer_scheduler.hpp b/third/asio/detail/winrt_timer_scheduler.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_timer_scheduler.hpp rename to third/asio/detail/winrt_timer_scheduler.hpp diff --git a/sdk/third/asio/detail/winrt_utils.hpp b/third/asio/detail/winrt_utils.hpp similarity index 100% rename from sdk/third/asio/detail/winrt_utils.hpp rename to third/asio/detail/winrt_utils.hpp diff --git a/sdk/third/asio/detail/winsock_init.hpp b/third/asio/detail/winsock_init.hpp similarity index 100% rename from sdk/third/asio/detail/winsock_init.hpp rename to third/asio/detail/winsock_init.hpp diff --git a/sdk/third/asio/detail/work_dispatcher.hpp b/third/asio/detail/work_dispatcher.hpp similarity index 100% rename from sdk/third/asio/detail/work_dispatcher.hpp rename to third/asio/detail/work_dispatcher.hpp diff --git a/sdk/third/asio/detail/wrapped_handler.hpp b/third/asio/detail/wrapped_handler.hpp similarity index 100% rename from sdk/third/asio/detail/wrapped_handler.hpp rename to third/asio/detail/wrapped_handler.hpp diff --git a/sdk/third/asio/dispatch.hpp b/third/asio/dispatch.hpp similarity index 100% rename from sdk/third/asio/dispatch.hpp rename to third/asio/dispatch.hpp diff --git a/sdk/third/asio/error.hpp b/third/asio/error.hpp similarity index 100% rename from sdk/third/asio/error.hpp rename to third/asio/error.hpp diff --git a/sdk/third/asio/error_code.hpp b/third/asio/error_code.hpp similarity index 100% rename from sdk/third/asio/error_code.hpp rename to third/asio/error_code.hpp diff --git a/sdk/third/asio/execution.hpp b/third/asio/execution.hpp similarity index 100% rename from sdk/third/asio/execution.hpp rename to third/asio/execution.hpp diff --git a/sdk/third/asio/execution/allocator.hpp b/third/asio/execution/allocator.hpp similarity index 100% rename from sdk/third/asio/execution/allocator.hpp rename to third/asio/execution/allocator.hpp diff --git a/sdk/third/asio/execution/any_executor.hpp b/third/asio/execution/any_executor.hpp similarity index 100% rename from sdk/third/asio/execution/any_executor.hpp rename to third/asio/execution/any_executor.hpp diff --git a/sdk/third/asio/execution/bad_executor.hpp b/third/asio/execution/bad_executor.hpp similarity index 100% rename from sdk/third/asio/execution/bad_executor.hpp rename to third/asio/execution/bad_executor.hpp diff --git a/sdk/third/asio/execution/blocking.hpp b/third/asio/execution/blocking.hpp similarity index 100% rename from sdk/third/asio/execution/blocking.hpp rename to third/asio/execution/blocking.hpp diff --git a/sdk/third/asio/execution/blocking_adaptation.hpp b/third/asio/execution/blocking_adaptation.hpp similarity index 100% rename from sdk/third/asio/execution/blocking_adaptation.hpp rename to third/asio/execution/blocking_adaptation.hpp diff --git a/sdk/third/asio/execution/bulk_execute.hpp b/third/asio/execution/bulk_execute.hpp similarity index 100% rename from sdk/third/asio/execution/bulk_execute.hpp rename to third/asio/execution/bulk_execute.hpp diff --git a/sdk/third/asio/execution/bulk_guarantee.hpp b/third/asio/execution/bulk_guarantee.hpp similarity index 100% rename from sdk/third/asio/execution/bulk_guarantee.hpp rename to third/asio/execution/bulk_guarantee.hpp diff --git a/sdk/third/asio/execution/connect.hpp b/third/asio/execution/connect.hpp similarity index 100% rename from sdk/third/asio/execution/connect.hpp rename to third/asio/execution/connect.hpp diff --git a/sdk/third/asio/execution/context.hpp b/third/asio/execution/context.hpp similarity index 100% rename from sdk/third/asio/execution/context.hpp rename to third/asio/execution/context.hpp diff --git a/sdk/third/asio/execution/context_as.hpp b/third/asio/execution/context_as.hpp similarity index 100% rename from sdk/third/asio/execution/context_as.hpp rename to third/asio/execution/context_as.hpp diff --git a/sdk/third/asio/execution/detail/as_invocable.hpp b/third/asio/execution/detail/as_invocable.hpp similarity index 100% rename from sdk/third/asio/execution/detail/as_invocable.hpp rename to third/asio/execution/detail/as_invocable.hpp diff --git a/sdk/third/asio/execution/detail/as_operation.hpp b/third/asio/execution/detail/as_operation.hpp similarity index 100% rename from sdk/third/asio/execution/detail/as_operation.hpp rename to third/asio/execution/detail/as_operation.hpp diff --git a/sdk/third/asio/execution/detail/as_receiver.hpp b/third/asio/execution/detail/as_receiver.hpp similarity index 100% rename from sdk/third/asio/execution/detail/as_receiver.hpp rename to third/asio/execution/detail/as_receiver.hpp diff --git a/sdk/third/asio/execution/detail/bulk_sender.hpp b/third/asio/execution/detail/bulk_sender.hpp similarity index 100% rename from sdk/third/asio/execution/detail/bulk_sender.hpp rename to third/asio/execution/detail/bulk_sender.hpp diff --git a/sdk/third/asio/execution/detail/submit_receiver.hpp b/third/asio/execution/detail/submit_receiver.hpp similarity index 100% rename from sdk/third/asio/execution/detail/submit_receiver.hpp rename to third/asio/execution/detail/submit_receiver.hpp diff --git a/sdk/third/asio/execution/detail/void_receiver.hpp b/third/asio/execution/detail/void_receiver.hpp similarity index 100% rename from sdk/third/asio/execution/detail/void_receiver.hpp rename to third/asio/execution/detail/void_receiver.hpp diff --git a/sdk/third/asio/execution/execute.hpp b/third/asio/execution/execute.hpp similarity index 100% rename from sdk/third/asio/execution/execute.hpp rename to third/asio/execution/execute.hpp diff --git a/sdk/third/asio/execution/executor.hpp b/third/asio/execution/executor.hpp similarity index 100% rename from sdk/third/asio/execution/executor.hpp rename to third/asio/execution/executor.hpp diff --git a/sdk/third/asio/execution/impl/bad_executor.ipp b/third/asio/execution/impl/bad_executor.ipp similarity index 100% rename from sdk/third/asio/execution/impl/bad_executor.ipp rename to third/asio/execution/impl/bad_executor.ipp diff --git a/sdk/third/asio/execution/impl/receiver_invocation_error.ipp b/third/asio/execution/impl/receiver_invocation_error.ipp similarity index 100% rename from sdk/third/asio/execution/impl/receiver_invocation_error.ipp rename to third/asio/execution/impl/receiver_invocation_error.ipp diff --git a/sdk/third/asio/execution/invocable_archetype.hpp b/third/asio/execution/invocable_archetype.hpp similarity index 100% rename from sdk/third/asio/execution/invocable_archetype.hpp rename to third/asio/execution/invocable_archetype.hpp diff --git a/sdk/third/asio/execution/mapping.hpp b/third/asio/execution/mapping.hpp similarity index 100% rename from sdk/third/asio/execution/mapping.hpp rename to third/asio/execution/mapping.hpp diff --git a/sdk/third/asio/execution/occupancy.hpp b/third/asio/execution/occupancy.hpp similarity index 100% rename from sdk/third/asio/execution/occupancy.hpp rename to third/asio/execution/occupancy.hpp diff --git a/sdk/third/asio/execution/operation_state.hpp b/third/asio/execution/operation_state.hpp similarity index 100% rename from sdk/third/asio/execution/operation_state.hpp rename to third/asio/execution/operation_state.hpp diff --git a/sdk/third/asio/execution/outstanding_work.hpp b/third/asio/execution/outstanding_work.hpp similarity index 100% rename from sdk/third/asio/execution/outstanding_work.hpp rename to third/asio/execution/outstanding_work.hpp diff --git a/sdk/third/asio/execution/prefer_only.hpp b/third/asio/execution/prefer_only.hpp similarity index 100% rename from sdk/third/asio/execution/prefer_only.hpp rename to third/asio/execution/prefer_only.hpp diff --git a/sdk/third/asio/execution/receiver.hpp b/third/asio/execution/receiver.hpp similarity index 100% rename from sdk/third/asio/execution/receiver.hpp rename to third/asio/execution/receiver.hpp diff --git a/sdk/third/asio/execution/receiver_invocation_error.hpp b/third/asio/execution/receiver_invocation_error.hpp similarity index 100% rename from sdk/third/asio/execution/receiver_invocation_error.hpp rename to third/asio/execution/receiver_invocation_error.hpp diff --git a/sdk/third/asio/execution/relationship.hpp b/third/asio/execution/relationship.hpp similarity index 100% rename from sdk/third/asio/execution/relationship.hpp rename to third/asio/execution/relationship.hpp diff --git a/sdk/third/asio/execution/schedule.hpp b/third/asio/execution/schedule.hpp similarity index 100% rename from sdk/third/asio/execution/schedule.hpp rename to third/asio/execution/schedule.hpp diff --git a/sdk/third/asio/execution/scheduler.hpp b/third/asio/execution/scheduler.hpp similarity index 100% rename from sdk/third/asio/execution/scheduler.hpp rename to third/asio/execution/scheduler.hpp diff --git a/sdk/third/asio/execution/sender.hpp b/third/asio/execution/sender.hpp similarity index 100% rename from sdk/third/asio/execution/sender.hpp rename to third/asio/execution/sender.hpp diff --git a/sdk/third/asio/execution/set_done.hpp b/third/asio/execution/set_done.hpp similarity index 100% rename from sdk/third/asio/execution/set_done.hpp rename to third/asio/execution/set_done.hpp diff --git a/sdk/third/asio/execution/set_error.hpp b/third/asio/execution/set_error.hpp similarity index 100% rename from sdk/third/asio/execution/set_error.hpp rename to third/asio/execution/set_error.hpp diff --git a/sdk/third/asio/execution/set_value.hpp b/third/asio/execution/set_value.hpp similarity index 100% rename from sdk/third/asio/execution/set_value.hpp rename to third/asio/execution/set_value.hpp diff --git a/sdk/third/asio/execution/start.hpp b/third/asio/execution/start.hpp similarity index 100% rename from sdk/third/asio/execution/start.hpp rename to third/asio/execution/start.hpp diff --git a/sdk/third/asio/execution/submit.hpp b/third/asio/execution/submit.hpp similarity index 100% rename from sdk/third/asio/execution/submit.hpp rename to third/asio/execution/submit.hpp diff --git a/sdk/third/asio/execution_context.hpp b/third/asio/execution_context.hpp similarity index 100% rename from sdk/third/asio/execution_context.hpp rename to third/asio/execution_context.hpp diff --git a/sdk/third/asio/executor.hpp b/third/asio/executor.hpp similarity index 100% rename from sdk/third/asio/executor.hpp rename to third/asio/executor.hpp diff --git a/sdk/third/asio/executor_work_guard.hpp b/third/asio/executor_work_guard.hpp similarity index 100% rename from sdk/third/asio/executor_work_guard.hpp rename to third/asio/executor_work_guard.hpp diff --git a/sdk/third/asio/experimental/append.hpp b/third/asio/experimental/append.hpp similarity index 100% rename from sdk/third/asio/experimental/append.hpp rename to third/asio/experimental/append.hpp diff --git a/sdk/third/asio/experimental/as_single.hpp b/third/asio/experimental/as_single.hpp similarity index 100% rename from sdk/third/asio/experimental/as_single.hpp rename to third/asio/experimental/as_single.hpp diff --git a/sdk/third/asio/experimental/as_tuple.hpp b/third/asio/experimental/as_tuple.hpp similarity index 100% rename from sdk/third/asio/experimental/as_tuple.hpp rename to third/asio/experimental/as_tuple.hpp diff --git a/sdk/third/asio/experimental/awaitable_operators.hpp b/third/asio/experimental/awaitable_operators.hpp similarity index 100% rename from sdk/third/asio/experimental/awaitable_operators.hpp rename to third/asio/experimental/awaitable_operators.hpp diff --git a/sdk/third/asio/experimental/basic_channel.hpp b/third/asio/experimental/basic_channel.hpp similarity index 100% rename from sdk/third/asio/experimental/basic_channel.hpp rename to third/asio/experimental/basic_channel.hpp diff --git a/sdk/third/asio/experimental/basic_concurrent_channel.hpp b/third/asio/experimental/basic_concurrent_channel.hpp similarity index 100% rename from sdk/third/asio/experimental/basic_concurrent_channel.hpp rename to third/asio/experimental/basic_concurrent_channel.hpp diff --git a/sdk/third/asio/experimental/cancellation_condition.hpp b/third/asio/experimental/cancellation_condition.hpp similarity index 100% rename from sdk/third/asio/experimental/cancellation_condition.hpp rename to third/asio/experimental/cancellation_condition.hpp diff --git a/sdk/third/asio/experimental/channel.hpp b/third/asio/experimental/channel.hpp similarity index 100% rename from sdk/third/asio/experimental/channel.hpp rename to third/asio/experimental/channel.hpp diff --git a/sdk/third/asio/experimental/channel_error.hpp b/third/asio/experimental/channel_error.hpp similarity index 100% rename from sdk/third/asio/experimental/channel_error.hpp rename to third/asio/experimental/channel_error.hpp diff --git a/sdk/third/asio/experimental/channel_traits.hpp b/third/asio/experimental/channel_traits.hpp similarity index 100% rename from sdk/third/asio/experimental/channel_traits.hpp rename to third/asio/experimental/channel_traits.hpp diff --git a/sdk/third/asio/experimental/co_spawn.hpp b/third/asio/experimental/co_spawn.hpp similarity index 100% rename from sdk/third/asio/experimental/co_spawn.hpp rename to third/asio/experimental/co_spawn.hpp diff --git a/sdk/third/asio/experimental/concurrent_channel.hpp b/third/asio/experimental/concurrent_channel.hpp similarity index 100% rename from sdk/third/asio/experimental/concurrent_channel.hpp rename to third/asio/experimental/concurrent_channel.hpp diff --git a/sdk/third/asio/experimental/coro.hpp b/third/asio/experimental/coro.hpp similarity index 100% rename from sdk/third/asio/experimental/coro.hpp rename to third/asio/experimental/coro.hpp diff --git a/sdk/third/asio/experimental/coro_traits.hpp b/third/asio/experimental/coro_traits.hpp similarity index 100% rename from sdk/third/asio/experimental/coro_traits.hpp rename to third/asio/experimental/coro_traits.hpp diff --git a/sdk/third/asio/experimental/deferred.hpp b/third/asio/experimental/deferred.hpp similarity index 100% rename from sdk/third/asio/experimental/deferred.hpp rename to third/asio/experimental/deferred.hpp diff --git a/sdk/third/asio/experimental/detail/channel_handler.hpp b/third/asio/experimental/detail/channel_handler.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_handler.hpp rename to third/asio/experimental/detail/channel_handler.hpp diff --git a/sdk/third/asio/experimental/detail/channel_message.hpp b/third/asio/experimental/detail/channel_message.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_message.hpp rename to third/asio/experimental/detail/channel_message.hpp diff --git a/sdk/third/asio/experimental/detail/channel_operation.hpp b/third/asio/experimental/detail/channel_operation.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_operation.hpp rename to third/asio/experimental/detail/channel_operation.hpp diff --git a/sdk/third/asio/experimental/detail/channel_payload.hpp b/third/asio/experimental/detail/channel_payload.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_payload.hpp rename to third/asio/experimental/detail/channel_payload.hpp diff --git a/sdk/third/asio/experimental/detail/channel_receive_op.hpp b/third/asio/experimental/detail/channel_receive_op.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_receive_op.hpp rename to third/asio/experimental/detail/channel_receive_op.hpp diff --git a/sdk/third/asio/experimental/detail/channel_send_functions.hpp b/third/asio/experimental/detail/channel_send_functions.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_send_functions.hpp rename to third/asio/experimental/detail/channel_send_functions.hpp diff --git a/sdk/third/asio/experimental/detail/channel_send_op.hpp b/third/asio/experimental/detail/channel_send_op.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_send_op.hpp rename to third/asio/experimental/detail/channel_send_op.hpp diff --git a/sdk/third/asio/experimental/detail/channel_service.hpp b/third/asio/experimental/detail/channel_service.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/channel_service.hpp rename to third/asio/experimental/detail/channel_service.hpp diff --git a/sdk/third/asio/experimental/detail/completion_handler_erasure.hpp b/third/asio/experimental/detail/completion_handler_erasure.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/completion_handler_erasure.hpp rename to third/asio/experimental/detail/completion_handler_erasure.hpp diff --git a/sdk/third/asio/experimental/detail/coro_promise_allocator.hpp b/third/asio/experimental/detail/coro_promise_allocator.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/coro_promise_allocator.hpp rename to third/asio/experimental/detail/coro_promise_allocator.hpp diff --git a/sdk/third/asio/experimental/detail/has_signature.hpp b/third/asio/experimental/detail/has_signature.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/has_signature.hpp rename to third/asio/experimental/detail/has_signature.hpp diff --git a/sdk/third/asio/experimental/detail/impl/channel_service.hpp b/third/asio/experimental/detail/impl/channel_service.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/impl/channel_service.hpp rename to third/asio/experimental/detail/impl/channel_service.hpp diff --git a/sdk/third/asio/experimental/detail/partial_promise.hpp b/third/asio/experimental/detail/partial_promise.hpp similarity index 100% rename from sdk/third/asio/experimental/detail/partial_promise.hpp rename to third/asio/experimental/detail/partial_promise.hpp diff --git a/sdk/third/asio/experimental/impl/as_single.hpp b/third/asio/experimental/impl/as_single.hpp similarity index 100% rename from sdk/third/asio/experimental/impl/as_single.hpp rename to third/asio/experimental/impl/as_single.hpp diff --git a/sdk/third/asio/experimental/impl/channel_error.ipp b/third/asio/experimental/impl/channel_error.ipp similarity index 100% rename from sdk/third/asio/experimental/impl/channel_error.ipp rename to third/asio/experimental/impl/channel_error.ipp diff --git a/sdk/third/asio/experimental/impl/coro.hpp b/third/asio/experimental/impl/coro.hpp similarity index 100% rename from sdk/third/asio/experimental/impl/coro.hpp rename to third/asio/experimental/impl/coro.hpp diff --git a/sdk/third/asio/experimental/impl/parallel_group.hpp b/third/asio/experimental/impl/parallel_group.hpp similarity index 100% rename from sdk/third/asio/experimental/impl/parallel_group.hpp rename to third/asio/experimental/impl/parallel_group.hpp diff --git a/sdk/third/asio/experimental/impl/promise.hpp b/third/asio/experimental/impl/promise.hpp similarity index 100% rename from sdk/third/asio/experimental/impl/promise.hpp rename to third/asio/experimental/impl/promise.hpp diff --git a/sdk/third/asio/experimental/impl/use_coro.hpp b/third/asio/experimental/impl/use_coro.hpp similarity index 100% rename from sdk/third/asio/experimental/impl/use_coro.hpp rename to third/asio/experimental/impl/use_coro.hpp diff --git a/sdk/third/asio/experimental/parallel_group.hpp b/third/asio/experimental/parallel_group.hpp similarity index 100% rename from sdk/third/asio/experimental/parallel_group.hpp rename to third/asio/experimental/parallel_group.hpp diff --git a/sdk/third/asio/experimental/prepend.hpp b/third/asio/experimental/prepend.hpp similarity index 100% rename from sdk/third/asio/experimental/prepend.hpp rename to third/asio/experimental/prepend.hpp diff --git a/sdk/third/asio/experimental/promise.hpp b/third/asio/experimental/promise.hpp similarity index 100% rename from sdk/third/asio/experimental/promise.hpp rename to third/asio/experimental/promise.hpp diff --git a/sdk/third/asio/experimental/use_coro.hpp b/third/asio/experimental/use_coro.hpp similarity index 100% rename from sdk/third/asio/experimental/use_coro.hpp rename to third/asio/experimental/use_coro.hpp diff --git a/sdk/third/asio/file_base.hpp b/third/asio/file_base.hpp similarity index 100% rename from sdk/third/asio/file_base.hpp rename to third/asio/file_base.hpp diff --git a/sdk/third/asio/generic/basic_endpoint.hpp b/third/asio/generic/basic_endpoint.hpp similarity index 100% rename from sdk/third/asio/generic/basic_endpoint.hpp rename to third/asio/generic/basic_endpoint.hpp diff --git a/sdk/third/asio/generic/datagram_protocol.hpp b/third/asio/generic/datagram_protocol.hpp similarity index 100% rename from sdk/third/asio/generic/datagram_protocol.hpp rename to third/asio/generic/datagram_protocol.hpp diff --git a/sdk/third/asio/generic/detail/endpoint.hpp b/third/asio/generic/detail/endpoint.hpp similarity index 100% rename from sdk/third/asio/generic/detail/endpoint.hpp rename to third/asio/generic/detail/endpoint.hpp diff --git a/sdk/third/asio/generic/detail/impl/endpoint.ipp b/third/asio/generic/detail/impl/endpoint.ipp similarity index 100% rename from sdk/third/asio/generic/detail/impl/endpoint.ipp rename to third/asio/generic/detail/impl/endpoint.ipp diff --git a/sdk/third/asio/generic/raw_protocol.hpp b/third/asio/generic/raw_protocol.hpp similarity index 100% rename from sdk/third/asio/generic/raw_protocol.hpp rename to third/asio/generic/raw_protocol.hpp diff --git a/sdk/third/asio/generic/seq_packet_protocol.hpp b/third/asio/generic/seq_packet_protocol.hpp similarity index 100% rename from sdk/third/asio/generic/seq_packet_protocol.hpp rename to third/asio/generic/seq_packet_protocol.hpp diff --git a/sdk/third/asio/generic/stream_protocol.hpp b/third/asio/generic/stream_protocol.hpp similarity index 100% rename from sdk/third/asio/generic/stream_protocol.hpp rename to third/asio/generic/stream_protocol.hpp diff --git a/sdk/third/asio/handler_alloc_hook.hpp b/third/asio/handler_alloc_hook.hpp similarity index 100% rename from sdk/third/asio/handler_alloc_hook.hpp rename to third/asio/handler_alloc_hook.hpp diff --git a/sdk/third/asio/handler_continuation_hook.hpp b/third/asio/handler_continuation_hook.hpp similarity index 100% rename from sdk/third/asio/handler_continuation_hook.hpp rename to third/asio/handler_continuation_hook.hpp diff --git a/sdk/third/asio/handler_invoke_hook.hpp b/third/asio/handler_invoke_hook.hpp similarity index 100% rename from sdk/third/asio/handler_invoke_hook.hpp rename to third/asio/handler_invoke_hook.hpp diff --git a/sdk/third/asio/high_resolution_timer.hpp b/third/asio/high_resolution_timer.hpp similarity index 100% rename from sdk/third/asio/high_resolution_timer.hpp rename to third/asio/high_resolution_timer.hpp diff --git a/sdk/third/asio/impl/any_io_executor.ipp b/third/asio/impl/any_io_executor.ipp similarity index 100% rename from sdk/third/asio/impl/any_io_executor.ipp rename to third/asio/impl/any_io_executor.ipp diff --git a/sdk/third/asio/impl/append.hpp b/third/asio/impl/append.hpp similarity index 100% rename from sdk/third/asio/impl/append.hpp rename to third/asio/impl/append.hpp diff --git a/sdk/third/asio/impl/as_tuple.hpp b/third/asio/impl/as_tuple.hpp similarity index 100% rename from sdk/third/asio/impl/as_tuple.hpp rename to third/asio/impl/as_tuple.hpp diff --git a/sdk/third/asio/impl/awaitable.hpp b/third/asio/impl/awaitable.hpp similarity index 100% rename from sdk/third/asio/impl/awaitable.hpp rename to third/asio/impl/awaitable.hpp diff --git a/sdk/third/asio/impl/buffered_read_stream.hpp b/third/asio/impl/buffered_read_stream.hpp similarity index 100% rename from sdk/third/asio/impl/buffered_read_stream.hpp rename to third/asio/impl/buffered_read_stream.hpp diff --git a/sdk/third/asio/impl/buffered_write_stream.hpp b/third/asio/impl/buffered_write_stream.hpp similarity index 100% rename from sdk/third/asio/impl/buffered_write_stream.hpp rename to third/asio/impl/buffered_write_stream.hpp diff --git a/sdk/third/asio/impl/cancellation_signal.ipp b/third/asio/impl/cancellation_signal.ipp similarity index 100% rename from sdk/third/asio/impl/cancellation_signal.ipp rename to third/asio/impl/cancellation_signal.ipp diff --git a/sdk/third/asio/impl/co_spawn.hpp b/third/asio/impl/co_spawn.hpp similarity index 100% rename from sdk/third/asio/impl/co_spawn.hpp rename to third/asio/impl/co_spawn.hpp diff --git a/sdk/third/asio/impl/connect.hpp b/third/asio/impl/connect.hpp similarity index 100% rename from sdk/third/asio/impl/connect.hpp rename to third/asio/impl/connect.hpp diff --git a/sdk/third/asio/impl/connect_pipe.hpp b/third/asio/impl/connect_pipe.hpp similarity index 100% rename from sdk/third/asio/impl/connect_pipe.hpp rename to third/asio/impl/connect_pipe.hpp diff --git a/sdk/third/asio/impl/connect_pipe.ipp b/third/asio/impl/connect_pipe.ipp similarity index 100% rename from sdk/third/asio/impl/connect_pipe.ipp rename to third/asio/impl/connect_pipe.ipp diff --git a/sdk/third/asio/impl/defer.hpp b/third/asio/impl/defer.hpp similarity index 100% rename from sdk/third/asio/impl/defer.hpp rename to third/asio/impl/defer.hpp diff --git a/sdk/third/asio/impl/deferred.hpp b/third/asio/impl/deferred.hpp similarity index 100% rename from sdk/third/asio/impl/deferred.hpp rename to third/asio/impl/deferred.hpp diff --git a/sdk/third/asio/impl/detached.hpp b/third/asio/impl/detached.hpp similarity index 100% rename from sdk/third/asio/impl/detached.hpp rename to third/asio/impl/detached.hpp diff --git a/sdk/third/asio/impl/dispatch.hpp b/third/asio/impl/dispatch.hpp similarity index 100% rename from sdk/third/asio/impl/dispatch.hpp rename to third/asio/impl/dispatch.hpp diff --git a/sdk/third/asio/impl/error.ipp b/third/asio/impl/error.ipp similarity index 100% rename from sdk/third/asio/impl/error.ipp rename to third/asio/impl/error.ipp diff --git a/sdk/third/asio/impl/error_code.ipp b/third/asio/impl/error_code.ipp similarity index 100% rename from sdk/third/asio/impl/error_code.ipp rename to third/asio/impl/error_code.ipp diff --git a/sdk/third/asio/impl/execution_context.hpp b/third/asio/impl/execution_context.hpp similarity index 100% rename from sdk/third/asio/impl/execution_context.hpp rename to third/asio/impl/execution_context.hpp diff --git a/sdk/third/asio/impl/execution_context.ipp b/third/asio/impl/execution_context.ipp similarity index 100% rename from sdk/third/asio/impl/execution_context.ipp rename to third/asio/impl/execution_context.ipp diff --git a/sdk/third/asio/impl/executor.hpp b/third/asio/impl/executor.hpp similarity index 100% rename from sdk/third/asio/impl/executor.hpp rename to third/asio/impl/executor.hpp diff --git a/sdk/third/asio/impl/executor.ipp b/third/asio/impl/executor.ipp similarity index 100% rename from sdk/third/asio/impl/executor.ipp rename to third/asio/impl/executor.ipp diff --git a/sdk/third/asio/impl/handler_alloc_hook.ipp b/third/asio/impl/handler_alloc_hook.ipp similarity index 100% rename from sdk/third/asio/impl/handler_alloc_hook.ipp rename to third/asio/impl/handler_alloc_hook.ipp diff --git a/sdk/third/asio/impl/io_context.hpp b/third/asio/impl/io_context.hpp similarity index 100% rename from sdk/third/asio/impl/io_context.hpp rename to third/asio/impl/io_context.hpp diff --git a/sdk/third/asio/impl/io_context.ipp b/third/asio/impl/io_context.ipp similarity index 100% rename from sdk/third/asio/impl/io_context.ipp rename to third/asio/impl/io_context.ipp diff --git a/sdk/third/asio/impl/multiple_exceptions.ipp b/third/asio/impl/multiple_exceptions.ipp similarity index 100% rename from sdk/third/asio/impl/multiple_exceptions.ipp rename to third/asio/impl/multiple_exceptions.ipp diff --git a/sdk/third/asio/impl/post.hpp b/third/asio/impl/post.hpp similarity index 100% rename from sdk/third/asio/impl/post.hpp rename to third/asio/impl/post.hpp diff --git a/sdk/third/asio/impl/prepend.hpp b/third/asio/impl/prepend.hpp similarity index 100% rename from sdk/third/asio/impl/prepend.hpp rename to third/asio/impl/prepend.hpp diff --git a/sdk/third/asio/impl/read.hpp b/third/asio/impl/read.hpp similarity index 100% rename from sdk/third/asio/impl/read.hpp rename to third/asio/impl/read.hpp diff --git a/sdk/third/asio/impl/read_at.hpp b/third/asio/impl/read_at.hpp similarity index 100% rename from sdk/third/asio/impl/read_at.hpp rename to third/asio/impl/read_at.hpp diff --git a/sdk/third/asio/impl/read_until.hpp b/third/asio/impl/read_until.hpp similarity index 100% rename from sdk/third/asio/impl/read_until.hpp rename to third/asio/impl/read_until.hpp diff --git a/sdk/third/asio/impl/redirect_error.hpp b/third/asio/impl/redirect_error.hpp similarity index 100% rename from sdk/third/asio/impl/redirect_error.hpp rename to third/asio/impl/redirect_error.hpp diff --git a/sdk/third/asio/impl/serial_port_base.hpp b/third/asio/impl/serial_port_base.hpp similarity index 100% rename from sdk/third/asio/impl/serial_port_base.hpp rename to third/asio/impl/serial_port_base.hpp diff --git a/sdk/third/asio/impl/serial_port_base.ipp b/third/asio/impl/serial_port_base.ipp similarity index 100% rename from sdk/third/asio/impl/serial_port_base.ipp rename to third/asio/impl/serial_port_base.ipp diff --git a/sdk/third/asio/impl/spawn.hpp b/third/asio/impl/spawn.hpp similarity index 100% rename from sdk/third/asio/impl/spawn.hpp rename to third/asio/impl/spawn.hpp diff --git a/sdk/third/asio/impl/src.hpp b/third/asio/impl/src.hpp similarity index 100% rename from sdk/third/asio/impl/src.hpp rename to third/asio/impl/src.hpp diff --git a/sdk/third/asio/impl/system_context.hpp b/third/asio/impl/system_context.hpp similarity index 100% rename from sdk/third/asio/impl/system_context.hpp rename to third/asio/impl/system_context.hpp diff --git a/sdk/third/asio/impl/system_context.ipp b/third/asio/impl/system_context.ipp similarity index 100% rename from sdk/third/asio/impl/system_context.ipp rename to third/asio/impl/system_context.ipp diff --git a/sdk/third/asio/impl/system_executor.hpp b/third/asio/impl/system_executor.hpp similarity index 100% rename from sdk/third/asio/impl/system_executor.hpp rename to third/asio/impl/system_executor.hpp diff --git a/sdk/third/asio/impl/thread_pool.hpp b/third/asio/impl/thread_pool.hpp similarity index 100% rename from sdk/third/asio/impl/thread_pool.hpp rename to third/asio/impl/thread_pool.hpp diff --git a/sdk/third/asio/impl/thread_pool.ipp b/third/asio/impl/thread_pool.ipp similarity index 100% rename from sdk/third/asio/impl/thread_pool.ipp rename to third/asio/impl/thread_pool.ipp diff --git a/sdk/third/asio/impl/use_awaitable.hpp b/third/asio/impl/use_awaitable.hpp similarity index 100% rename from sdk/third/asio/impl/use_awaitable.hpp rename to third/asio/impl/use_awaitable.hpp diff --git a/sdk/third/asio/impl/use_future.hpp b/third/asio/impl/use_future.hpp similarity index 100% rename from sdk/third/asio/impl/use_future.hpp rename to third/asio/impl/use_future.hpp diff --git a/sdk/third/asio/impl/write.hpp b/third/asio/impl/write.hpp similarity index 100% rename from sdk/third/asio/impl/write.hpp rename to third/asio/impl/write.hpp diff --git a/sdk/third/asio/impl/write_at.hpp b/third/asio/impl/write_at.hpp similarity index 100% rename from sdk/third/asio/impl/write_at.hpp rename to third/asio/impl/write_at.hpp diff --git a/sdk/third/asio/io_context.hpp b/third/asio/io_context.hpp similarity index 100% rename from sdk/third/asio/io_context.hpp rename to third/asio/io_context.hpp diff --git a/sdk/third/asio/io_context_strand.hpp b/third/asio/io_context_strand.hpp similarity index 100% rename from sdk/third/asio/io_context_strand.hpp rename to third/asio/io_context_strand.hpp diff --git a/sdk/third/asio/io_service.hpp b/third/asio/io_service.hpp similarity index 100% rename from sdk/third/asio/io_service.hpp rename to third/asio/io_service.hpp diff --git a/sdk/third/asio/io_service_strand.hpp b/third/asio/io_service_strand.hpp similarity index 100% rename from sdk/third/asio/io_service_strand.hpp rename to third/asio/io_service_strand.hpp diff --git a/sdk/third/asio/ip/address.hpp b/third/asio/ip/address.hpp similarity index 100% rename from sdk/third/asio/ip/address.hpp rename to third/asio/ip/address.hpp diff --git a/sdk/third/asio/ip/address_v4.hpp b/third/asio/ip/address_v4.hpp similarity index 100% rename from sdk/third/asio/ip/address_v4.hpp rename to third/asio/ip/address_v4.hpp diff --git a/sdk/third/asio/ip/address_v4_iterator.hpp b/third/asio/ip/address_v4_iterator.hpp similarity index 100% rename from sdk/third/asio/ip/address_v4_iterator.hpp rename to third/asio/ip/address_v4_iterator.hpp diff --git a/sdk/third/asio/ip/address_v4_range.hpp b/third/asio/ip/address_v4_range.hpp similarity index 100% rename from sdk/third/asio/ip/address_v4_range.hpp rename to third/asio/ip/address_v4_range.hpp diff --git a/sdk/third/asio/ip/address_v6.hpp b/third/asio/ip/address_v6.hpp similarity index 100% rename from sdk/third/asio/ip/address_v6.hpp rename to third/asio/ip/address_v6.hpp diff --git a/sdk/third/asio/ip/address_v6_iterator.hpp b/third/asio/ip/address_v6_iterator.hpp similarity index 100% rename from sdk/third/asio/ip/address_v6_iterator.hpp rename to third/asio/ip/address_v6_iterator.hpp diff --git a/sdk/third/asio/ip/address_v6_range.hpp b/third/asio/ip/address_v6_range.hpp similarity index 100% rename from sdk/third/asio/ip/address_v6_range.hpp rename to third/asio/ip/address_v6_range.hpp diff --git a/sdk/third/asio/ip/bad_address_cast.hpp b/third/asio/ip/bad_address_cast.hpp similarity index 100% rename from sdk/third/asio/ip/bad_address_cast.hpp rename to third/asio/ip/bad_address_cast.hpp diff --git a/sdk/third/asio/ip/basic_endpoint.hpp b/third/asio/ip/basic_endpoint.hpp similarity index 100% rename from sdk/third/asio/ip/basic_endpoint.hpp rename to third/asio/ip/basic_endpoint.hpp diff --git a/sdk/third/asio/ip/basic_resolver.hpp b/third/asio/ip/basic_resolver.hpp similarity index 100% rename from sdk/third/asio/ip/basic_resolver.hpp rename to third/asio/ip/basic_resolver.hpp diff --git a/sdk/third/asio/ip/basic_resolver_entry.hpp b/third/asio/ip/basic_resolver_entry.hpp similarity index 100% rename from sdk/third/asio/ip/basic_resolver_entry.hpp rename to third/asio/ip/basic_resolver_entry.hpp diff --git a/sdk/third/asio/ip/basic_resolver_iterator.hpp b/third/asio/ip/basic_resolver_iterator.hpp similarity index 100% rename from sdk/third/asio/ip/basic_resolver_iterator.hpp rename to third/asio/ip/basic_resolver_iterator.hpp diff --git a/sdk/third/asio/ip/basic_resolver_query.hpp b/third/asio/ip/basic_resolver_query.hpp similarity index 100% rename from sdk/third/asio/ip/basic_resolver_query.hpp rename to third/asio/ip/basic_resolver_query.hpp diff --git a/sdk/third/asio/ip/basic_resolver_results.hpp b/third/asio/ip/basic_resolver_results.hpp similarity index 100% rename from sdk/third/asio/ip/basic_resolver_results.hpp rename to third/asio/ip/basic_resolver_results.hpp diff --git a/sdk/third/asio/ip/detail/endpoint.hpp b/third/asio/ip/detail/endpoint.hpp similarity index 100% rename from sdk/third/asio/ip/detail/endpoint.hpp rename to third/asio/ip/detail/endpoint.hpp diff --git a/sdk/third/asio/ip/detail/impl/endpoint.ipp b/third/asio/ip/detail/impl/endpoint.ipp similarity index 100% rename from sdk/third/asio/ip/detail/impl/endpoint.ipp rename to third/asio/ip/detail/impl/endpoint.ipp diff --git a/sdk/third/asio/ip/detail/socket_option.hpp b/third/asio/ip/detail/socket_option.hpp similarity index 100% rename from sdk/third/asio/ip/detail/socket_option.hpp rename to third/asio/ip/detail/socket_option.hpp diff --git a/sdk/third/asio/ip/host_name.hpp b/third/asio/ip/host_name.hpp similarity index 100% rename from sdk/third/asio/ip/host_name.hpp rename to third/asio/ip/host_name.hpp diff --git a/sdk/third/asio/ip/icmp.hpp b/third/asio/ip/icmp.hpp similarity index 100% rename from sdk/third/asio/ip/icmp.hpp rename to third/asio/ip/icmp.hpp diff --git a/sdk/third/asio/ip/impl/address.hpp b/third/asio/ip/impl/address.hpp similarity index 100% rename from sdk/third/asio/ip/impl/address.hpp rename to third/asio/ip/impl/address.hpp diff --git a/sdk/third/asio/ip/impl/address.ipp b/third/asio/ip/impl/address.ipp similarity index 100% rename from sdk/third/asio/ip/impl/address.ipp rename to third/asio/ip/impl/address.ipp diff --git a/sdk/third/asio/ip/impl/address_v4.hpp b/third/asio/ip/impl/address_v4.hpp similarity index 100% rename from sdk/third/asio/ip/impl/address_v4.hpp rename to third/asio/ip/impl/address_v4.hpp diff --git a/sdk/third/asio/ip/impl/address_v4.ipp b/third/asio/ip/impl/address_v4.ipp similarity index 100% rename from sdk/third/asio/ip/impl/address_v4.ipp rename to third/asio/ip/impl/address_v4.ipp diff --git a/sdk/third/asio/ip/impl/address_v6.hpp b/third/asio/ip/impl/address_v6.hpp similarity index 100% rename from sdk/third/asio/ip/impl/address_v6.hpp rename to third/asio/ip/impl/address_v6.hpp diff --git a/sdk/third/asio/ip/impl/address_v6.ipp b/third/asio/ip/impl/address_v6.ipp similarity index 100% rename from sdk/third/asio/ip/impl/address_v6.ipp rename to third/asio/ip/impl/address_v6.ipp diff --git a/sdk/third/asio/ip/impl/basic_endpoint.hpp b/third/asio/ip/impl/basic_endpoint.hpp similarity index 100% rename from sdk/third/asio/ip/impl/basic_endpoint.hpp rename to third/asio/ip/impl/basic_endpoint.hpp diff --git a/sdk/third/asio/ip/impl/host_name.ipp b/third/asio/ip/impl/host_name.ipp similarity index 100% rename from sdk/third/asio/ip/impl/host_name.ipp rename to third/asio/ip/impl/host_name.ipp diff --git a/sdk/third/asio/ip/impl/network_v4.hpp b/third/asio/ip/impl/network_v4.hpp similarity index 100% rename from sdk/third/asio/ip/impl/network_v4.hpp rename to third/asio/ip/impl/network_v4.hpp diff --git a/sdk/third/asio/ip/impl/network_v4.ipp b/third/asio/ip/impl/network_v4.ipp similarity index 100% rename from sdk/third/asio/ip/impl/network_v4.ipp rename to third/asio/ip/impl/network_v4.ipp diff --git a/sdk/third/asio/ip/impl/network_v6.hpp b/third/asio/ip/impl/network_v6.hpp similarity index 100% rename from sdk/third/asio/ip/impl/network_v6.hpp rename to third/asio/ip/impl/network_v6.hpp diff --git a/sdk/third/asio/ip/impl/network_v6.ipp b/third/asio/ip/impl/network_v6.ipp similarity index 100% rename from sdk/third/asio/ip/impl/network_v6.ipp rename to third/asio/ip/impl/network_v6.ipp diff --git a/sdk/third/asio/ip/multicast.hpp b/third/asio/ip/multicast.hpp similarity index 100% rename from sdk/third/asio/ip/multicast.hpp rename to third/asio/ip/multicast.hpp diff --git a/sdk/third/asio/ip/network_v4.hpp b/third/asio/ip/network_v4.hpp similarity index 100% rename from sdk/third/asio/ip/network_v4.hpp rename to third/asio/ip/network_v4.hpp diff --git a/sdk/third/asio/ip/network_v6.hpp b/third/asio/ip/network_v6.hpp similarity index 100% rename from sdk/third/asio/ip/network_v6.hpp rename to third/asio/ip/network_v6.hpp diff --git a/sdk/third/asio/ip/resolver_base.hpp b/third/asio/ip/resolver_base.hpp similarity index 100% rename from sdk/third/asio/ip/resolver_base.hpp rename to third/asio/ip/resolver_base.hpp diff --git a/sdk/third/asio/ip/resolver_query_base.hpp b/third/asio/ip/resolver_query_base.hpp similarity index 100% rename from sdk/third/asio/ip/resolver_query_base.hpp rename to third/asio/ip/resolver_query_base.hpp diff --git a/sdk/third/asio/ip/tcp.hpp b/third/asio/ip/tcp.hpp similarity index 100% rename from sdk/third/asio/ip/tcp.hpp rename to third/asio/ip/tcp.hpp diff --git a/sdk/third/asio/ip/udp.hpp b/third/asio/ip/udp.hpp similarity index 100% rename from sdk/third/asio/ip/udp.hpp rename to third/asio/ip/udp.hpp diff --git a/sdk/third/asio/ip/unicast.hpp b/third/asio/ip/unicast.hpp similarity index 100% rename from sdk/third/asio/ip/unicast.hpp rename to third/asio/ip/unicast.hpp diff --git a/sdk/third/asio/ip/v6_only.hpp b/third/asio/ip/v6_only.hpp similarity index 100% rename from sdk/third/asio/ip/v6_only.hpp rename to third/asio/ip/v6_only.hpp diff --git a/sdk/third/asio/is_applicable_property.hpp b/third/asio/is_applicable_property.hpp similarity index 100% rename from sdk/third/asio/is_applicable_property.hpp rename to third/asio/is_applicable_property.hpp diff --git a/sdk/third/asio/is_contiguous_iterator.hpp b/third/asio/is_contiguous_iterator.hpp similarity index 100% rename from sdk/third/asio/is_contiguous_iterator.hpp rename to third/asio/is_contiguous_iterator.hpp diff --git a/sdk/third/asio/is_executor.hpp b/third/asio/is_executor.hpp similarity index 100% rename from sdk/third/asio/is_executor.hpp rename to third/asio/is_executor.hpp diff --git a/sdk/third/asio/is_read_buffered.hpp b/third/asio/is_read_buffered.hpp similarity index 100% rename from sdk/third/asio/is_read_buffered.hpp rename to third/asio/is_read_buffered.hpp diff --git a/sdk/third/asio/is_write_buffered.hpp b/third/asio/is_write_buffered.hpp similarity index 100% rename from sdk/third/asio/is_write_buffered.hpp rename to third/asio/is_write_buffered.hpp diff --git a/sdk/third/asio/local/basic_endpoint.hpp b/third/asio/local/basic_endpoint.hpp similarity index 100% rename from sdk/third/asio/local/basic_endpoint.hpp rename to third/asio/local/basic_endpoint.hpp diff --git a/sdk/third/asio/local/connect_pair.hpp b/third/asio/local/connect_pair.hpp similarity index 100% rename from sdk/third/asio/local/connect_pair.hpp rename to third/asio/local/connect_pair.hpp diff --git a/sdk/third/asio/local/datagram_protocol.hpp b/third/asio/local/datagram_protocol.hpp similarity index 100% rename from sdk/third/asio/local/datagram_protocol.hpp rename to third/asio/local/datagram_protocol.hpp diff --git a/sdk/third/asio/local/detail/endpoint.hpp b/third/asio/local/detail/endpoint.hpp similarity index 100% rename from sdk/third/asio/local/detail/endpoint.hpp rename to third/asio/local/detail/endpoint.hpp diff --git a/sdk/third/asio/local/detail/impl/endpoint.ipp b/third/asio/local/detail/impl/endpoint.ipp similarity index 100% rename from sdk/third/asio/local/detail/impl/endpoint.ipp rename to third/asio/local/detail/impl/endpoint.ipp diff --git a/sdk/third/asio/local/stream_protocol.hpp b/third/asio/local/stream_protocol.hpp similarity index 100% rename from sdk/third/asio/local/stream_protocol.hpp rename to third/asio/local/stream_protocol.hpp diff --git a/sdk/third/asio/multiple_exceptions.hpp b/third/asio/multiple_exceptions.hpp similarity index 100% rename from sdk/third/asio/multiple_exceptions.hpp rename to third/asio/multiple_exceptions.hpp diff --git a/sdk/third/asio/packaged_task.hpp b/third/asio/packaged_task.hpp similarity index 100% rename from sdk/third/asio/packaged_task.hpp rename to third/asio/packaged_task.hpp diff --git a/sdk/third/asio/placeholders.hpp b/third/asio/placeholders.hpp similarity index 100% rename from sdk/third/asio/placeholders.hpp rename to third/asio/placeholders.hpp diff --git a/sdk/third/asio/posix/basic_descriptor.hpp b/third/asio/posix/basic_descriptor.hpp similarity index 100% rename from sdk/third/asio/posix/basic_descriptor.hpp rename to third/asio/posix/basic_descriptor.hpp diff --git a/sdk/third/asio/posix/basic_stream_descriptor.hpp b/third/asio/posix/basic_stream_descriptor.hpp similarity index 100% rename from sdk/third/asio/posix/basic_stream_descriptor.hpp rename to third/asio/posix/basic_stream_descriptor.hpp diff --git a/sdk/third/asio/posix/descriptor.hpp b/third/asio/posix/descriptor.hpp similarity index 100% rename from sdk/third/asio/posix/descriptor.hpp rename to third/asio/posix/descriptor.hpp diff --git a/sdk/third/asio/posix/descriptor_base.hpp b/third/asio/posix/descriptor_base.hpp similarity index 100% rename from sdk/third/asio/posix/descriptor_base.hpp rename to third/asio/posix/descriptor_base.hpp diff --git a/sdk/third/asio/posix/stream_descriptor.hpp b/third/asio/posix/stream_descriptor.hpp similarity index 100% rename from sdk/third/asio/posix/stream_descriptor.hpp rename to third/asio/posix/stream_descriptor.hpp diff --git a/sdk/third/asio/post.hpp b/third/asio/post.hpp similarity index 100% rename from sdk/third/asio/post.hpp rename to third/asio/post.hpp diff --git a/sdk/third/asio/prefer.hpp b/third/asio/prefer.hpp similarity index 100% rename from sdk/third/asio/prefer.hpp rename to third/asio/prefer.hpp diff --git a/sdk/third/asio/prepend.hpp b/third/asio/prepend.hpp similarity index 100% rename from sdk/third/asio/prepend.hpp rename to third/asio/prepend.hpp diff --git a/sdk/third/asio/query.hpp b/third/asio/query.hpp similarity index 100% rename from sdk/third/asio/query.hpp rename to third/asio/query.hpp diff --git a/sdk/third/asio/random_access_file.hpp b/third/asio/random_access_file.hpp similarity index 100% rename from sdk/third/asio/random_access_file.hpp rename to third/asio/random_access_file.hpp diff --git a/sdk/third/asio/read.hpp b/third/asio/read.hpp similarity index 100% rename from sdk/third/asio/read.hpp rename to third/asio/read.hpp diff --git a/sdk/third/asio/read_at.hpp b/third/asio/read_at.hpp similarity index 100% rename from sdk/third/asio/read_at.hpp rename to third/asio/read_at.hpp diff --git a/sdk/third/asio/read_until.hpp b/third/asio/read_until.hpp similarity index 100% rename from sdk/third/asio/read_until.hpp rename to third/asio/read_until.hpp diff --git a/sdk/third/asio/readable_pipe.hpp b/third/asio/readable_pipe.hpp similarity index 100% rename from sdk/third/asio/readable_pipe.hpp rename to third/asio/readable_pipe.hpp diff --git a/sdk/third/asio/recycling_allocator.hpp b/third/asio/recycling_allocator.hpp similarity index 100% rename from sdk/third/asio/recycling_allocator.hpp rename to third/asio/recycling_allocator.hpp diff --git a/sdk/third/asio/redirect_error.hpp b/third/asio/redirect_error.hpp similarity index 100% rename from sdk/third/asio/redirect_error.hpp rename to third/asio/redirect_error.hpp diff --git a/sdk/third/asio/registered_buffer.hpp b/third/asio/registered_buffer.hpp similarity index 100% rename from sdk/third/asio/registered_buffer.hpp rename to third/asio/registered_buffer.hpp diff --git a/sdk/third/asio/require.hpp b/third/asio/require.hpp similarity index 100% rename from sdk/third/asio/require.hpp rename to third/asio/require.hpp diff --git a/sdk/third/asio/require_concept.hpp b/third/asio/require_concept.hpp similarity index 100% rename from sdk/third/asio/require_concept.hpp rename to third/asio/require_concept.hpp diff --git a/sdk/third/asio/serial_port.hpp b/third/asio/serial_port.hpp similarity index 100% rename from sdk/third/asio/serial_port.hpp rename to third/asio/serial_port.hpp diff --git a/sdk/third/asio/serial_port_base.hpp b/third/asio/serial_port_base.hpp similarity index 100% rename from sdk/third/asio/serial_port_base.hpp rename to third/asio/serial_port_base.hpp diff --git a/sdk/third/asio/signal_set.hpp b/third/asio/signal_set.hpp similarity index 100% rename from sdk/third/asio/signal_set.hpp rename to third/asio/signal_set.hpp diff --git a/sdk/third/asio/socket_base.hpp b/third/asio/socket_base.hpp similarity index 100% rename from sdk/third/asio/socket_base.hpp rename to third/asio/socket_base.hpp diff --git a/sdk/third/asio/spawn.hpp b/third/asio/spawn.hpp similarity index 100% rename from sdk/third/asio/spawn.hpp rename to third/asio/spawn.hpp diff --git a/sdk/third/asio/ssl.hpp b/third/asio/ssl.hpp similarity index 100% rename from sdk/third/asio/ssl.hpp rename to third/asio/ssl.hpp diff --git a/sdk/third/asio/ssl/context.hpp b/third/asio/ssl/context.hpp similarity index 100% rename from sdk/third/asio/ssl/context.hpp rename to third/asio/ssl/context.hpp diff --git a/sdk/third/asio/ssl/context_base.hpp b/third/asio/ssl/context_base.hpp similarity index 100% rename from sdk/third/asio/ssl/context_base.hpp rename to third/asio/ssl/context_base.hpp diff --git a/sdk/third/asio/ssl/detail/buffered_handshake_op.hpp b/third/asio/ssl/detail/buffered_handshake_op.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/buffered_handshake_op.hpp rename to third/asio/ssl/detail/buffered_handshake_op.hpp diff --git a/sdk/third/asio/ssl/detail/engine.hpp b/third/asio/ssl/detail/engine.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/engine.hpp rename to third/asio/ssl/detail/engine.hpp diff --git a/sdk/third/asio/ssl/detail/handshake_op.hpp b/third/asio/ssl/detail/handshake_op.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/handshake_op.hpp rename to third/asio/ssl/detail/handshake_op.hpp diff --git a/sdk/third/asio/ssl/detail/impl/engine.ipp b/third/asio/ssl/detail/impl/engine.ipp similarity index 100% rename from sdk/third/asio/ssl/detail/impl/engine.ipp rename to third/asio/ssl/detail/impl/engine.ipp diff --git a/sdk/third/asio/ssl/detail/impl/openssl_init.ipp b/third/asio/ssl/detail/impl/openssl_init.ipp similarity index 100% rename from sdk/third/asio/ssl/detail/impl/openssl_init.ipp rename to third/asio/ssl/detail/impl/openssl_init.ipp diff --git a/sdk/third/asio/ssl/detail/io.hpp b/third/asio/ssl/detail/io.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/io.hpp rename to third/asio/ssl/detail/io.hpp diff --git a/sdk/third/asio/ssl/detail/openssl_init.hpp b/third/asio/ssl/detail/openssl_init.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/openssl_init.hpp rename to third/asio/ssl/detail/openssl_init.hpp diff --git a/sdk/third/asio/ssl/detail/openssl_types.hpp b/third/asio/ssl/detail/openssl_types.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/openssl_types.hpp rename to third/asio/ssl/detail/openssl_types.hpp diff --git a/sdk/third/asio/ssl/detail/password_callback.hpp b/third/asio/ssl/detail/password_callback.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/password_callback.hpp rename to third/asio/ssl/detail/password_callback.hpp diff --git a/sdk/third/asio/ssl/detail/read_op.hpp b/third/asio/ssl/detail/read_op.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/read_op.hpp rename to third/asio/ssl/detail/read_op.hpp diff --git a/sdk/third/asio/ssl/detail/shutdown_op.hpp b/third/asio/ssl/detail/shutdown_op.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/shutdown_op.hpp rename to third/asio/ssl/detail/shutdown_op.hpp diff --git a/sdk/third/asio/ssl/detail/stream_core.hpp b/third/asio/ssl/detail/stream_core.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/stream_core.hpp rename to third/asio/ssl/detail/stream_core.hpp diff --git a/sdk/third/asio/ssl/detail/verify_callback.hpp b/third/asio/ssl/detail/verify_callback.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/verify_callback.hpp rename to third/asio/ssl/detail/verify_callback.hpp diff --git a/sdk/third/asio/ssl/detail/write_op.hpp b/third/asio/ssl/detail/write_op.hpp similarity index 100% rename from sdk/third/asio/ssl/detail/write_op.hpp rename to third/asio/ssl/detail/write_op.hpp diff --git a/sdk/third/asio/ssl/error.hpp b/third/asio/ssl/error.hpp similarity index 100% rename from sdk/third/asio/ssl/error.hpp rename to third/asio/ssl/error.hpp diff --git a/sdk/third/asio/ssl/host_name_verification.hpp b/third/asio/ssl/host_name_verification.hpp similarity index 100% rename from sdk/third/asio/ssl/host_name_verification.hpp rename to third/asio/ssl/host_name_verification.hpp diff --git a/sdk/third/asio/ssl/impl/context.hpp b/third/asio/ssl/impl/context.hpp similarity index 100% rename from sdk/third/asio/ssl/impl/context.hpp rename to third/asio/ssl/impl/context.hpp diff --git a/sdk/third/asio/ssl/impl/context.ipp b/third/asio/ssl/impl/context.ipp similarity index 100% rename from sdk/third/asio/ssl/impl/context.ipp rename to third/asio/ssl/impl/context.ipp diff --git a/sdk/third/asio/ssl/impl/error.ipp b/third/asio/ssl/impl/error.ipp similarity index 100% rename from sdk/third/asio/ssl/impl/error.ipp rename to third/asio/ssl/impl/error.ipp diff --git a/sdk/third/asio/ssl/impl/host_name_verification.ipp b/third/asio/ssl/impl/host_name_verification.ipp similarity index 100% rename from sdk/third/asio/ssl/impl/host_name_verification.ipp rename to third/asio/ssl/impl/host_name_verification.ipp diff --git a/sdk/third/asio/ssl/impl/rfc2818_verification.ipp b/third/asio/ssl/impl/rfc2818_verification.ipp similarity index 100% rename from sdk/third/asio/ssl/impl/rfc2818_verification.ipp rename to third/asio/ssl/impl/rfc2818_verification.ipp diff --git a/sdk/third/asio/ssl/impl/src.hpp b/third/asio/ssl/impl/src.hpp similarity index 100% rename from sdk/third/asio/ssl/impl/src.hpp rename to third/asio/ssl/impl/src.hpp diff --git a/sdk/third/asio/ssl/rfc2818_verification.hpp b/third/asio/ssl/rfc2818_verification.hpp similarity index 100% rename from sdk/third/asio/ssl/rfc2818_verification.hpp rename to third/asio/ssl/rfc2818_verification.hpp diff --git a/sdk/third/asio/ssl/stream.hpp b/third/asio/ssl/stream.hpp similarity index 100% rename from sdk/third/asio/ssl/stream.hpp rename to third/asio/ssl/stream.hpp diff --git a/sdk/third/asio/ssl/stream_base.hpp b/third/asio/ssl/stream_base.hpp similarity index 100% rename from sdk/third/asio/ssl/stream_base.hpp rename to third/asio/ssl/stream_base.hpp diff --git a/sdk/third/asio/ssl/verify_context.hpp b/third/asio/ssl/verify_context.hpp similarity index 100% rename from sdk/third/asio/ssl/verify_context.hpp rename to third/asio/ssl/verify_context.hpp diff --git a/sdk/third/asio/ssl/verify_mode.hpp b/third/asio/ssl/verify_mode.hpp similarity index 100% rename from sdk/third/asio/ssl/verify_mode.hpp rename to third/asio/ssl/verify_mode.hpp diff --git a/sdk/third/asio/static_thread_pool.hpp b/third/asio/static_thread_pool.hpp similarity index 100% rename from sdk/third/asio/static_thread_pool.hpp rename to third/asio/static_thread_pool.hpp diff --git a/sdk/third/asio/steady_timer.hpp b/third/asio/steady_timer.hpp similarity index 100% rename from sdk/third/asio/steady_timer.hpp rename to third/asio/steady_timer.hpp diff --git a/sdk/third/asio/strand.hpp b/third/asio/strand.hpp similarity index 100% rename from sdk/third/asio/strand.hpp rename to third/asio/strand.hpp diff --git a/sdk/third/asio/stream_file.hpp b/third/asio/stream_file.hpp similarity index 100% rename from sdk/third/asio/stream_file.hpp rename to third/asio/stream_file.hpp diff --git a/sdk/third/asio/streambuf.hpp b/third/asio/streambuf.hpp similarity index 100% rename from sdk/third/asio/streambuf.hpp rename to third/asio/streambuf.hpp diff --git a/sdk/third/asio/system_context.hpp b/third/asio/system_context.hpp similarity index 100% rename from sdk/third/asio/system_context.hpp rename to third/asio/system_context.hpp diff --git a/sdk/third/asio/system_error.hpp b/third/asio/system_error.hpp similarity index 100% rename from sdk/third/asio/system_error.hpp rename to third/asio/system_error.hpp diff --git a/sdk/third/asio/system_executor.hpp b/third/asio/system_executor.hpp similarity index 100% rename from sdk/third/asio/system_executor.hpp rename to third/asio/system_executor.hpp diff --git a/sdk/third/asio/system_timer.hpp b/third/asio/system_timer.hpp similarity index 100% rename from sdk/third/asio/system_timer.hpp rename to third/asio/system_timer.hpp diff --git a/sdk/third/asio/this_coro.hpp b/third/asio/this_coro.hpp similarity index 100% rename from sdk/third/asio/this_coro.hpp rename to third/asio/this_coro.hpp diff --git a/sdk/third/asio/thread.hpp b/third/asio/thread.hpp similarity index 100% rename from sdk/third/asio/thread.hpp rename to third/asio/thread.hpp diff --git a/sdk/third/asio/thread_pool.hpp b/third/asio/thread_pool.hpp similarity index 100% rename from sdk/third/asio/thread_pool.hpp rename to third/asio/thread_pool.hpp diff --git a/sdk/third/asio/time_traits.hpp b/third/asio/time_traits.hpp similarity index 100% rename from sdk/third/asio/time_traits.hpp rename to third/asio/time_traits.hpp diff --git a/sdk/third/asio/traits/bulk_execute_free.hpp b/third/asio/traits/bulk_execute_free.hpp similarity index 100% rename from sdk/third/asio/traits/bulk_execute_free.hpp rename to third/asio/traits/bulk_execute_free.hpp diff --git a/sdk/third/asio/traits/bulk_execute_member.hpp b/third/asio/traits/bulk_execute_member.hpp similarity index 100% rename from sdk/third/asio/traits/bulk_execute_member.hpp rename to third/asio/traits/bulk_execute_member.hpp diff --git a/sdk/third/asio/traits/connect_free.hpp b/third/asio/traits/connect_free.hpp similarity index 100% rename from sdk/third/asio/traits/connect_free.hpp rename to third/asio/traits/connect_free.hpp diff --git a/sdk/third/asio/traits/connect_member.hpp b/third/asio/traits/connect_member.hpp similarity index 100% rename from sdk/third/asio/traits/connect_member.hpp rename to third/asio/traits/connect_member.hpp diff --git a/sdk/third/asio/traits/equality_comparable.hpp b/third/asio/traits/equality_comparable.hpp similarity index 100% rename from sdk/third/asio/traits/equality_comparable.hpp rename to third/asio/traits/equality_comparable.hpp diff --git a/sdk/third/asio/traits/execute_free.hpp b/third/asio/traits/execute_free.hpp similarity index 100% rename from sdk/third/asio/traits/execute_free.hpp rename to third/asio/traits/execute_free.hpp diff --git a/sdk/third/asio/traits/execute_member.hpp b/third/asio/traits/execute_member.hpp similarity index 100% rename from sdk/third/asio/traits/execute_member.hpp rename to third/asio/traits/execute_member.hpp diff --git a/sdk/third/asio/traits/prefer_free.hpp b/third/asio/traits/prefer_free.hpp similarity index 100% rename from sdk/third/asio/traits/prefer_free.hpp rename to third/asio/traits/prefer_free.hpp diff --git a/sdk/third/asio/traits/prefer_member.hpp b/third/asio/traits/prefer_member.hpp similarity index 100% rename from sdk/third/asio/traits/prefer_member.hpp rename to third/asio/traits/prefer_member.hpp diff --git a/sdk/third/asio/traits/query_free.hpp b/third/asio/traits/query_free.hpp similarity index 100% rename from sdk/third/asio/traits/query_free.hpp rename to third/asio/traits/query_free.hpp diff --git a/sdk/third/asio/traits/query_member.hpp b/third/asio/traits/query_member.hpp similarity index 100% rename from sdk/third/asio/traits/query_member.hpp rename to third/asio/traits/query_member.hpp diff --git a/sdk/third/asio/traits/query_static_constexpr_member.hpp b/third/asio/traits/query_static_constexpr_member.hpp similarity index 100% rename from sdk/third/asio/traits/query_static_constexpr_member.hpp rename to third/asio/traits/query_static_constexpr_member.hpp diff --git a/sdk/third/asio/traits/require_concept_free.hpp b/third/asio/traits/require_concept_free.hpp similarity index 100% rename from sdk/third/asio/traits/require_concept_free.hpp rename to third/asio/traits/require_concept_free.hpp diff --git a/sdk/third/asio/traits/require_concept_member.hpp b/third/asio/traits/require_concept_member.hpp similarity index 100% rename from sdk/third/asio/traits/require_concept_member.hpp rename to third/asio/traits/require_concept_member.hpp diff --git a/sdk/third/asio/traits/require_free.hpp b/third/asio/traits/require_free.hpp similarity index 100% rename from sdk/third/asio/traits/require_free.hpp rename to third/asio/traits/require_free.hpp diff --git a/sdk/third/asio/traits/require_member.hpp b/third/asio/traits/require_member.hpp similarity index 100% rename from sdk/third/asio/traits/require_member.hpp rename to third/asio/traits/require_member.hpp diff --git a/sdk/third/asio/traits/schedule_free.hpp b/third/asio/traits/schedule_free.hpp similarity index 100% rename from sdk/third/asio/traits/schedule_free.hpp rename to third/asio/traits/schedule_free.hpp diff --git a/sdk/third/asio/traits/schedule_member.hpp b/third/asio/traits/schedule_member.hpp similarity index 100% rename from sdk/third/asio/traits/schedule_member.hpp rename to third/asio/traits/schedule_member.hpp diff --git a/sdk/third/asio/traits/set_done_free.hpp b/third/asio/traits/set_done_free.hpp similarity index 100% rename from sdk/third/asio/traits/set_done_free.hpp rename to third/asio/traits/set_done_free.hpp diff --git a/sdk/third/asio/traits/set_done_member.hpp b/third/asio/traits/set_done_member.hpp similarity index 100% rename from sdk/third/asio/traits/set_done_member.hpp rename to third/asio/traits/set_done_member.hpp diff --git a/sdk/third/asio/traits/set_error_free.hpp b/third/asio/traits/set_error_free.hpp similarity index 100% rename from sdk/third/asio/traits/set_error_free.hpp rename to third/asio/traits/set_error_free.hpp diff --git a/sdk/third/asio/traits/set_error_member.hpp b/third/asio/traits/set_error_member.hpp similarity index 100% rename from sdk/third/asio/traits/set_error_member.hpp rename to third/asio/traits/set_error_member.hpp diff --git a/sdk/third/asio/traits/set_value_free.hpp b/third/asio/traits/set_value_free.hpp similarity index 100% rename from sdk/third/asio/traits/set_value_free.hpp rename to third/asio/traits/set_value_free.hpp diff --git a/sdk/third/asio/traits/set_value_member.hpp b/third/asio/traits/set_value_member.hpp similarity index 100% rename from sdk/third/asio/traits/set_value_member.hpp rename to third/asio/traits/set_value_member.hpp diff --git a/sdk/third/asio/traits/start_free.hpp b/third/asio/traits/start_free.hpp similarity index 100% rename from sdk/third/asio/traits/start_free.hpp rename to third/asio/traits/start_free.hpp diff --git a/sdk/third/asio/traits/start_member.hpp b/third/asio/traits/start_member.hpp similarity index 100% rename from sdk/third/asio/traits/start_member.hpp rename to third/asio/traits/start_member.hpp diff --git a/sdk/third/asio/traits/static_query.hpp b/third/asio/traits/static_query.hpp similarity index 100% rename from sdk/third/asio/traits/static_query.hpp rename to third/asio/traits/static_query.hpp diff --git a/sdk/third/asio/traits/static_require.hpp b/third/asio/traits/static_require.hpp similarity index 100% rename from sdk/third/asio/traits/static_require.hpp rename to third/asio/traits/static_require.hpp diff --git a/sdk/third/asio/traits/static_require_concept.hpp b/third/asio/traits/static_require_concept.hpp similarity index 100% rename from sdk/third/asio/traits/static_require_concept.hpp rename to third/asio/traits/static_require_concept.hpp diff --git a/sdk/third/asio/traits/submit_free.hpp b/third/asio/traits/submit_free.hpp similarity index 100% rename from sdk/third/asio/traits/submit_free.hpp rename to third/asio/traits/submit_free.hpp diff --git a/sdk/third/asio/traits/submit_member.hpp b/third/asio/traits/submit_member.hpp similarity index 100% rename from sdk/third/asio/traits/submit_member.hpp rename to third/asio/traits/submit_member.hpp diff --git a/sdk/third/asio/ts/buffer.hpp b/third/asio/ts/buffer.hpp similarity index 100% rename from sdk/third/asio/ts/buffer.hpp rename to third/asio/ts/buffer.hpp diff --git a/sdk/third/asio/ts/executor.hpp b/third/asio/ts/executor.hpp similarity index 100% rename from sdk/third/asio/ts/executor.hpp rename to third/asio/ts/executor.hpp diff --git a/sdk/third/asio/ts/internet.hpp b/third/asio/ts/internet.hpp similarity index 100% rename from sdk/third/asio/ts/internet.hpp rename to third/asio/ts/internet.hpp diff --git a/sdk/third/asio/ts/io_context.hpp b/third/asio/ts/io_context.hpp similarity index 100% rename from sdk/third/asio/ts/io_context.hpp rename to third/asio/ts/io_context.hpp diff --git a/sdk/third/asio/ts/net.hpp b/third/asio/ts/net.hpp similarity index 100% rename from sdk/third/asio/ts/net.hpp rename to third/asio/ts/net.hpp diff --git a/sdk/third/asio/ts/netfwd.hpp b/third/asio/ts/netfwd.hpp similarity index 100% rename from sdk/third/asio/ts/netfwd.hpp rename to third/asio/ts/netfwd.hpp diff --git a/sdk/third/asio/ts/socket.hpp b/third/asio/ts/socket.hpp similarity index 100% rename from sdk/third/asio/ts/socket.hpp rename to third/asio/ts/socket.hpp diff --git a/sdk/third/asio/ts/timer.hpp b/third/asio/ts/timer.hpp similarity index 100% rename from sdk/third/asio/ts/timer.hpp rename to third/asio/ts/timer.hpp diff --git a/sdk/third/asio/unyield.hpp b/third/asio/unyield.hpp similarity index 100% rename from sdk/third/asio/unyield.hpp rename to third/asio/unyield.hpp diff --git a/sdk/third/asio/use_awaitable.hpp b/third/asio/use_awaitable.hpp similarity index 100% rename from sdk/third/asio/use_awaitable.hpp rename to third/asio/use_awaitable.hpp diff --git a/sdk/third/asio/use_future.hpp b/third/asio/use_future.hpp similarity index 100% rename from sdk/third/asio/use_future.hpp rename to third/asio/use_future.hpp diff --git a/sdk/third/asio/uses_executor.hpp b/third/asio/uses_executor.hpp similarity index 100% rename from sdk/third/asio/uses_executor.hpp rename to third/asio/uses_executor.hpp diff --git a/sdk/third/asio/version.hpp b/third/asio/version.hpp similarity index 100% rename from sdk/third/asio/version.hpp rename to third/asio/version.hpp diff --git a/sdk/third/asio/wait_traits.hpp b/third/asio/wait_traits.hpp similarity index 100% rename from sdk/third/asio/wait_traits.hpp rename to third/asio/wait_traits.hpp diff --git a/sdk/third/asio/windows/basic_object_handle.hpp b/third/asio/windows/basic_object_handle.hpp similarity index 100% rename from sdk/third/asio/windows/basic_object_handle.hpp rename to third/asio/windows/basic_object_handle.hpp diff --git a/sdk/third/asio/windows/basic_overlapped_handle.hpp b/third/asio/windows/basic_overlapped_handle.hpp similarity index 100% rename from sdk/third/asio/windows/basic_overlapped_handle.hpp rename to third/asio/windows/basic_overlapped_handle.hpp diff --git a/sdk/third/asio/windows/basic_random_access_handle.hpp b/third/asio/windows/basic_random_access_handle.hpp similarity index 100% rename from sdk/third/asio/windows/basic_random_access_handle.hpp rename to third/asio/windows/basic_random_access_handle.hpp diff --git a/sdk/third/asio/windows/basic_stream_handle.hpp b/third/asio/windows/basic_stream_handle.hpp similarity index 100% rename from sdk/third/asio/windows/basic_stream_handle.hpp rename to third/asio/windows/basic_stream_handle.hpp diff --git a/sdk/third/asio/windows/object_handle.hpp b/third/asio/windows/object_handle.hpp similarity index 100% rename from sdk/third/asio/windows/object_handle.hpp rename to third/asio/windows/object_handle.hpp diff --git a/sdk/third/asio/windows/overlapped_handle.hpp b/third/asio/windows/overlapped_handle.hpp similarity index 100% rename from sdk/third/asio/windows/overlapped_handle.hpp rename to third/asio/windows/overlapped_handle.hpp diff --git a/sdk/third/asio/windows/overlapped_ptr.hpp b/third/asio/windows/overlapped_ptr.hpp similarity index 100% rename from sdk/third/asio/windows/overlapped_ptr.hpp rename to third/asio/windows/overlapped_ptr.hpp diff --git a/sdk/third/asio/windows/random_access_handle.hpp b/third/asio/windows/random_access_handle.hpp similarity index 100% rename from sdk/third/asio/windows/random_access_handle.hpp rename to third/asio/windows/random_access_handle.hpp diff --git a/sdk/third/asio/windows/stream_handle.hpp b/third/asio/windows/stream_handle.hpp similarity index 100% rename from sdk/third/asio/windows/stream_handle.hpp rename to third/asio/windows/stream_handle.hpp diff --git a/sdk/third/asio/writable_pipe.hpp b/third/asio/writable_pipe.hpp similarity index 100% rename from sdk/third/asio/writable_pipe.hpp rename to third/asio/writable_pipe.hpp diff --git a/sdk/third/asio/write.hpp b/third/asio/write.hpp similarity index 100% rename from sdk/third/asio/write.hpp rename to third/asio/write.hpp diff --git a/sdk/third/asio/write_at.hpp b/third/asio/write_at.hpp similarity index 100% rename from sdk/third/asio/write_at.hpp rename to third/asio/write_at.hpp diff --git a/sdk/third/asio/yield.hpp b/third/asio/yield.hpp similarity index 100% rename from sdk/third/asio/yield.hpp rename to third/asio/yield.hpp diff --git a/sdk/third/mdns.h b/third/mdns.h similarity index 100% rename from sdk/third/mdns.h rename to third/mdns.h diff --git a/sdk/third/rapidjson/allocators.h b/third/rapidjson/allocators.h similarity index 100% rename from sdk/third/rapidjson/allocators.h rename to third/rapidjson/allocators.h diff --git a/sdk/third/rapidjson/cursorstreamwrapper.h b/third/rapidjson/cursorstreamwrapper.h similarity index 100% rename from sdk/third/rapidjson/cursorstreamwrapper.h rename to third/rapidjson/cursorstreamwrapper.h diff --git a/sdk/third/rapidjson/document.h b/third/rapidjson/document.h similarity index 100% rename from sdk/third/rapidjson/document.h rename to third/rapidjson/document.h diff --git a/sdk/third/rapidjson/encodedstream.h b/third/rapidjson/encodedstream.h similarity index 100% rename from sdk/third/rapidjson/encodedstream.h rename to third/rapidjson/encodedstream.h diff --git a/sdk/third/rapidjson/encodings.h b/third/rapidjson/encodings.h similarity index 100% rename from sdk/third/rapidjson/encodings.h rename to third/rapidjson/encodings.h diff --git a/sdk/third/rapidjson/error/en.h b/third/rapidjson/error/en.h similarity index 100% rename from sdk/third/rapidjson/error/en.h rename to third/rapidjson/error/en.h diff --git a/sdk/third/rapidjson/error/error.h b/third/rapidjson/error/error.h similarity index 100% rename from sdk/third/rapidjson/error/error.h rename to third/rapidjson/error/error.h diff --git a/sdk/third/rapidjson/filereadstream.h b/third/rapidjson/filereadstream.h similarity index 100% rename from sdk/third/rapidjson/filereadstream.h rename to third/rapidjson/filereadstream.h diff --git a/sdk/third/rapidjson/filewritestream.h b/third/rapidjson/filewritestream.h similarity index 100% rename from sdk/third/rapidjson/filewritestream.h rename to third/rapidjson/filewritestream.h diff --git a/sdk/third/rapidjson/fwd.h b/third/rapidjson/fwd.h similarity index 100% rename from sdk/third/rapidjson/fwd.h rename to third/rapidjson/fwd.h diff --git a/sdk/third/rapidjson/internal/biginteger.h b/third/rapidjson/internal/biginteger.h similarity index 100% rename from sdk/third/rapidjson/internal/biginteger.h rename to third/rapidjson/internal/biginteger.h diff --git a/sdk/third/rapidjson/internal/clzll.h b/third/rapidjson/internal/clzll.h similarity index 100% rename from sdk/third/rapidjson/internal/clzll.h rename to third/rapidjson/internal/clzll.h diff --git a/sdk/third/rapidjson/internal/diyfp.h b/third/rapidjson/internal/diyfp.h similarity index 100% rename from sdk/third/rapidjson/internal/diyfp.h rename to third/rapidjson/internal/diyfp.h diff --git a/sdk/third/rapidjson/internal/dtoa.h b/third/rapidjson/internal/dtoa.h similarity index 100% rename from sdk/third/rapidjson/internal/dtoa.h rename to third/rapidjson/internal/dtoa.h diff --git a/sdk/third/rapidjson/internal/ieee754.h b/third/rapidjson/internal/ieee754.h similarity index 100% rename from sdk/third/rapidjson/internal/ieee754.h rename to third/rapidjson/internal/ieee754.h diff --git a/sdk/third/rapidjson/internal/itoa.h b/third/rapidjson/internal/itoa.h similarity index 100% rename from sdk/third/rapidjson/internal/itoa.h rename to third/rapidjson/internal/itoa.h diff --git a/sdk/third/rapidjson/internal/meta.h b/third/rapidjson/internal/meta.h similarity index 100% rename from sdk/third/rapidjson/internal/meta.h rename to third/rapidjson/internal/meta.h diff --git a/sdk/third/rapidjson/internal/pow10.h b/third/rapidjson/internal/pow10.h similarity index 100% rename from sdk/third/rapidjson/internal/pow10.h rename to third/rapidjson/internal/pow10.h diff --git a/sdk/third/rapidjson/internal/regex.h b/third/rapidjson/internal/regex.h similarity index 100% rename from sdk/third/rapidjson/internal/regex.h rename to third/rapidjson/internal/regex.h diff --git a/sdk/third/rapidjson/internal/stack.h b/third/rapidjson/internal/stack.h similarity index 100% rename from sdk/third/rapidjson/internal/stack.h rename to third/rapidjson/internal/stack.h diff --git a/sdk/third/rapidjson/internal/strfunc.h b/third/rapidjson/internal/strfunc.h similarity index 100% rename from sdk/third/rapidjson/internal/strfunc.h rename to third/rapidjson/internal/strfunc.h diff --git a/sdk/third/rapidjson/internal/strtod.h b/third/rapidjson/internal/strtod.h similarity index 100% rename from sdk/third/rapidjson/internal/strtod.h rename to third/rapidjson/internal/strtod.h diff --git a/sdk/third/rapidjson/internal/swap.h b/third/rapidjson/internal/swap.h similarity index 100% rename from sdk/third/rapidjson/internal/swap.h rename to third/rapidjson/internal/swap.h diff --git a/sdk/third/rapidjson/istreamwrapper.h b/third/rapidjson/istreamwrapper.h similarity index 100% rename from sdk/third/rapidjson/istreamwrapper.h rename to third/rapidjson/istreamwrapper.h diff --git a/sdk/third/rapidjson/memorybuffer.h b/third/rapidjson/memorybuffer.h similarity index 100% rename from sdk/third/rapidjson/memorybuffer.h rename to third/rapidjson/memorybuffer.h diff --git a/sdk/third/rapidjson/memorystream.h b/third/rapidjson/memorystream.h similarity index 100% rename from sdk/third/rapidjson/memorystream.h rename to third/rapidjson/memorystream.h diff --git a/sdk/third/rapidjson/msinttypes/inttypes.h b/third/rapidjson/msinttypes/inttypes.h similarity index 100% rename from sdk/third/rapidjson/msinttypes/inttypes.h rename to third/rapidjson/msinttypes/inttypes.h diff --git a/sdk/third/rapidjson/msinttypes/stdint.h b/third/rapidjson/msinttypes/stdint.h similarity index 100% rename from sdk/third/rapidjson/msinttypes/stdint.h rename to third/rapidjson/msinttypes/stdint.h diff --git a/sdk/third/rapidjson/ostreamwrapper.h b/third/rapidjson/ostreamwrapper.h similarity index 100% rename from sdk/third/rapidjson/ostreamwrapper.h rename to third/rapidjson/ostreamwrapper.h diff --git a/sdk/third/rapidjson/pointer.h b/third/rapidjson/pointer.h similarity index 100% rename from sdk/third/rapidjson/pointer.h rename to third/rapidjson/pointer.h diff --git a/sdk/third/rapidjson/prettywriter.h b/third/rapidjson/prettywriter.h similarity index 100% rename from sdk/third/rapidjson/prettywriter.h rename to third/rapidjson/prettywriter.h diff --git a/sdk/third/rapidjson/rapidjson.h b/third/rapidjson/rapidjson.h similarity index 100% rename from sdk/third/rapidjson/rapidjson.h rename to third/rapidjson/rapidjson.h diff --git a/sdk/third/rapidjson/reader.h b/third/rapidjson/reader.h similarity index 100% rename from sdk/third/rapidjson/reader.h rename to third/rapidjson/reader.h diff --git a/sdk/third/rapidjson/schema.h b/third/rapidjson/schema.h similarity index 100% rename from sdk/third/rapidjson/schema.h rename to third/rapidjson/schema.h diff --git a/sdk/third/rapidjson/stream.h b/third/rapidjson/stream.h similarity index 100% rename from sdk/third/rapidjson/stream.h rename to third/rapidjson/stream.h diff --git a/sdk/third/rapidjson/stringbuffer.h b/third/rapidjson/stringbuffer.h similarity index 100% rename from sdk/third/rapidjson/stringbuffer.h rename to third/rapidjson/stringbuffer.h diff --git a/sdk/third/rapidjson/uri.h b/third/rapidjson/uri.h similarity index 100% rename from sdk/third/rapidjson/uri.h rename to third/rapidjson/uri.h diff --git a/sdk/third/rapidjson/writer.h b/third/rapidjson/writer.h similarity index 100% rename from sdk/third/rapidjson/writer.h rename to third/rapidjson/writer.h diff --git a/sdk/third/websocketpp/CMakeLists.txt b/third/websocketpp/CMakeLists.txt similarity index 100% rename from sdk/third/websocketpp/CMakeLists.txt rename to third/websocketpp/CMakeLists.txt diff --git a/sdk/third/websocketpp/base64/base64.hpp b/third/websocketpp/base64/base64.hpp similarity index 100% rename from sdk/third/websocketpp/base64/base64.hpp rename to third/websocketpp/base64/base64.hpp diff --git a/sdk/third/websocketpp/client.hpp b/third/websocketpp/client.hpp similarity index 100% rename from sdk/third/websocketpp/client.hpp rename to third/websocketpp/client.hpp diff --git a/sdk/third/websocketpp/close.hpp b/third/websocketpp/close.hpp similarity index 100% rename from sdk/third/websocketpp/close.hpp rename to third/websocketpp/close.hpp diff --git a/sdk/third/websocketpp/common/asio.hpp b/third/websocketpp/common/asio.hpp similarity index 100% rename from sdk/third/websocketpp/common/asio.hpp rename to third/websocketpp/common/asio.hpp diff --git a/sdk/third/websocketpp/common/asio_ssl.hpp b/third/websocketpp/common/asio_ssl.hpp similarity index 100% rename from sdk/third/websocketpp/common/asio_ssl.hpp rename to third/websocketpp/common/asio_ssl.hpp diff --git a/sdk/third/websocketpp/common/chrono.hpp b/third/websocketpp/common/chrono.hpp similarity index 100% rename from sdk/third/websocketpp/common/chrono.hpp rename to third/websocketpp/common/chrono.hpp diff --git a/sdk/third/websocketpp/common/connection_hdl.hpp b/third/websocketpp/common/connection_hdl.hpp similarity index 100% rename from sdk/third/websocketpp/common/connection_hdl.hpp rename to third/websocketpp/common/connection_hdl.hpp diff --git a/sdk/third/websocketpp/common/cpp11.hpp b/third/websocketpp/common/cpp11.hpp similarity index 100% rename from sdk/third/websocketpp/common/cpp11.hpp rename to third/websocketpp/common/cpp11.hpp diff --git a/sdk/third/websocketpp/common/functional.hpp b/third/websocketpp/common/functional.hpp similarity index 100% rename from sdk/third/websocketpp/common/functional.hpp rename to third/websocketpp/common/functional.hpp diff --git a/sdk/third/websocketpp/common/md5.hpp b/third/websocketpp/common/md5.hpp similarity index 100% rename from sdk/third/websocketpp/common/md5.hpp rename to third/websocketpp/common/md5.hpp diff --git a/sdk/third/websocketpp/common/memory.hpp b/third/websocketpp/common/memory.hpp similarity index 100% rename from sdk/third/websocketpp/common/memory.hpp rename to third/websocketpp/common/memory.hpp diff --git a/sdk/third/websocketpp/common/network.hpp b/third/websocketpp/common/network.hpp similarity index 100% rename from sdk/third/websocketpp/common/network.hpp rename to third/websocketpp/common/network.hpp diff --git a/sdk/third/websocketpp/common/platforms.hpp b/third/websocketpp/common/platforms.hpp similarity index 100% rename from sdk/third/websocketpp/common/platforms.hpp rename to third/websocketpp/common/platforms.hpp diff --git a/sdk/third/websocketpp/common/random.hpp b/third/websocketpp/common/random.hpp similarity index 100% rename from sdk/third/websocketpp/common/random.hpp rename to third/websocketpp/common/random.hpp diff --git a/sdk/third/websocketpp/common/regex.hpp b/third/websocketpp/common/regex.hpp similarity index 100% rename from sdk/third/websocketpp/common/regex.hpp rename to third/websocketpp/common/regex.hpp diff --git a/sdk/third/websocketpp/common/stdint.hpp b/third/websocketpp/common/stdint.hpp similarity index 100% rename from sdk/third/websocketpp/common/stdint.hpp rename to third/websocketpp/common/stdint.hpp diff --git a/sdk/third/websocketpp/common/system_error.hpp b/third/websocketpp/common/system_error.hpp similarity index 100% rename from sdk/third/websocketpp/common/system_error.hpp rename to third/websocketpp/common/system_error.hpp diff --git a/sdk/third/websocketpp/common/thread.hpp b/third/websocketpp/common/thread.hpp similarity index 100% rename from sdk/third/websocketpp/common/thread.hpp rename to third/websocketpp/common/thread.hpp diff --git a/sdk/third/websocketpp/common/time.hpp b/third/websocketpp/common/time.hpp similarity index 100% rename from sdk/third/websocketpp/common/time.hpp rename to third/websocketpp/common/time.hpp diff --git a/sdk/third/websocketpp/common/type_traits.hpp b/third/websocketpp/common/type_traits.hpp old mode 100755 new mode 100644 similarity index 100% rename from sdk/third/websocketpp/common/type_traits.hpp rename to third/websocketpp/common/type_traits.hpp diff --git a/sdk/third/websocketpp/concurrency/basic.hpp b/third/websocketpp/concurrency/basic.hpp similarity index 100% rename from sdk/third/websocketpp/concurrency/basic.hpp rename to third/websocketpp/concurrency/basic.hpp diff --git a/sdk/third/websocketpp/concurrency/none.hpp b/third/websocketpp/concurrency/none.hpp similarity index 100% rename from sdk/third/websocketpp/concurrency/none.hpp rename to third/websocketpp/concurrency/none.hpp diff --git a/sdk/third/websocketpp/config/asio.hpp b/third/websocketpp/config/asio.hpp similarity index 100% rename from sdk/third/websocketpp/config/asio.hpp rename to third/websocketpp/config/asio.hpp diff --git a/sdk/third/websocketpp/config/asio_client.hpp b/third/websocketpp/config/asio_client.hpp similarity index 100% rename from sdk/third/websocketpp/config/asio_client.hpp rename to third/websocketpp/config/asio_client.hpp diff --git a/sdk/third/websocketpp/config/asio_no_tls.hpp b/third/websocketpp/config/asio_no_tls.hpp similarity index 100% rename from sdk/third/websocketpp/config/asio_no_tls.hpp rename to third/websocketpp/config/asio_no_tls.hpp diff --git a/sdk/third/websocketpp/config/asio_no_tls_client.hpp b/third/websocketpp/config/asio_no_tls_client.hpp similarity index 100% rename from sdk/third/websocketpp/config/asio_no_tls_client.hpp rename to third/websocketpp/config/asio_no_tls_client.hpp diff --git a/sdk/third/websocketpp/config/boost_config.hpp b/third/websocketpp/config/boost_config.hpp similarity index 100% rename from sdk/third/websocketpp/config/boost_config.hpp rename to third/websocketpp/config/boost_config.hpp diff --git a/sdk/third/websocketpp/config/core.hpp b/third/websocketpp/config/core.hpp similarity index 100% rename from sdk/third/websocketpp/config/core.hpp rename to third/websocketpp/config/core.hpp diff --git a/sdk/third/websocketpp/config/core_client.hpp b/third/websocketpp/config/core_client.hpp similarity index 100% rename from sdk/third/websocketpp/config/core_client.hpp rename to third/websocketpp/config/core_client.hpp diff --git a/sdk/third/websocketpp/config/debug.hpp b/third/websocketpp/config/debug.hpp similarity index 100% rename from sdk/third/websocketpp/config/debug.hpp rename to third/websocketpp/config/debug.hpp diff --git a/sdk/third/websocketpp/config/debug_asio.hpp b/third/websocketpp/config/debug_asio.hpp similarity index 100% rename from sdk/third/websocketpp/config/debug_asio.hpp rename to third/websocketpp/config/debug_asio.hpp diff --git a/sdk/third/websocketpp/config/debug_asio_no_tls.hpp b/third/websocketpp/config/debug_asio_no_tls.hpp similarity index 100% rename from sdk/third/websocketpp/config/debug_asio_no_tls.hpp rename to third/websocketpp/config/debug_asio_no_tls.hpp diff --git a/sdk/third/websocketpp/config/minimal_client.hpp b/third/websocketpp/config/minimal_client.hpp similarity index 100% rename from sdk/third/websocketpp/config/minimal_client.hpp rename to third/websocketpp/config/minimal_client.hpp diff --git a/sdk/third/websocketpp/config/minimal_server.hpp b/third/websocketpp/config/minimal_server.hpp similarity index 100% rename from sdk/third/websocketpp/config/minimal_server.hpp rename to third/websocketpp/config/minimal_server.hpp diff --git a/sdk/third/websocketpp/connection.hpp b/third/websocketpp/connection.hpp similarity index 100% rename from sdk/third/websocketpp/connection.hpp rename to third/websocketpp/connection.hpp diff --git a/sdk/third/websocketpp/connection_base.hpp b/third/websocketpp/connection_base.hpp similarity index 100% rename from sdk/third/websocketpp/connection_base.hpp rename to third/websocketpp/connection_base.hpp diff --git a/sdk/third/websocketpp/endpoint.hpp b/third/websocketpp/endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/endpoint.hpp rename to third/websocketpp/endpoint.hpp diff --git a/sdk/third/websocketpp/endpoint_base.hpp b/third/websocketpp/endpoint_base.hpp similarity index 100% rename from sdk/third/websocketpp/endpoint_base.hpp rename to third/websocketpp/endpoint_base.hpp diff --git a/sdk/third/websocketpp/error.hpp b/third/websocketpp/error.hpp similarity index 100% rename from sdk/third/websocketpp/error.hpp rename to third/websocketpp/error.hpp diff --git a/sdk/third/websocketpp/extensions/extension.hpp b/third/websocketpp/extensions/extension.hpp similarity index 100% rename from sdk/third/websocketpp/extensions/extension.hpp rename to third/websocketpp/extensions/extension.hpp diff --git a/sdk/third/websocketpp/extensions/permessage_deflate/disabled.hpp b/third/websocketpp/extensions/permessage_deflate/disabled.hpp similarity index 100% rename from sdk/third/websocketpp/extensions/permessage_deflate/disabled.hpp rename to third/websocketpp/extensions/permessage_deflate/disabled.hpp diff --git a/sdk/third/websocketpp/extensions/permessage_deflate/enabled.hpp b/third/websocketpp/extensions/permessage_deflate/enabled.hpp similarity index 100% rename from sdk/third/websocketpp/extensions/permessage_deflate/enabled.hpp rename to third/websocketpp/extensions/permessage_deflate/enabled.hpp diff --git a/sdk/third/websocketpp/frame.hpp b/third/websocketpp/frame.hpp similarity index 100% rename from sdk/third/websocketpp/frame.hpp rename to third/websocketpp/frame.hpp diff --git a/sdk/third/websocketpp/http/constants.hpp b/third/websocketpp/http/constants.hpp similarity index 100% rename from sdk/third/websocketpp/http/constants.hpp rename to third/websocketpp/http/constants.hpp diff --git a/sdk/third/websocketpp/http/impl/parser.hpp b/third/websocketpp/http/impl/parser.hpp similarity index 100% rename from sdk/third/websocketpp/http/impl/parser.hpp rename to third/websocketpp/http/impl/parser.hpp diff --git a/sdk/third/websocketpp/http/impl/request.hpp b/third/websocketpp/http/impl/request.hpp similarity index 100% rename from sdk/third/websocketpp/http/impl/request.hpp rename to third/websocketpp/http/impl/request.hpp diff --git a/sdk/third/websocketpp/http/impl/response.hpp b/third/websocketpp/http/impl/response.hpp similarity index 100% rename from sdk/third/websocketpp/http/impl/response.hpp rename to third/websocketpp/http/impl/response.hpp diff --git a/sdk/third/websocketpp/http/parser.hpp b/third/websocketpp/http/parser.hpp similarity index 100% rename from sdk/third/websocketpp/http/parser.hpp rename to third/websocketpp/http/parser.hpp diff --git a/sdk/third/websocketpp/http/request.hpp b/third/websocketpp/http/request.hpp similarity index 100% rename from sdk/third/websocketpp/http/request.hpp rename to third/websocketpp/http/request.hpp diff --git a/sdk/third/websocketpp/http/response.hpp b/third/websocketpp/http/response.hpp similarity index 100% rename from sdk/third/websocketpp/http/response.hpp rename to third/websocketpp/http/response.hpp diff --git a/sdk/third/websocketpp/impl/connection_impl.hpp b/third/websocketpp/impl/connection_impl.hpp similarity index 100% rename from sdk/third/websocketpp/impl/connection_impl.hpp rename to third/websocketpp/impl/connection_impl.hpp diff --git a/sdk/third/websocketpp/impl/endpoint_impl.hpp b/third/websocketpp/impl/endpoint_impl.hpp similarity index 100% rename from sdk/third/websocketpp/impl/endpoint_impl.hpp rename to third/websocketpp/impl/endpoint_impl.hpp diff --git a/sdk/third/websocketpp/impl/utilities_impl.hpp b/third/websocketpp/impl/utilities_impl.hpp similarity index 100% rename from sdk/third/websocketpp/impl/utilities_impl.hpp rename to third/websocketpp/impl/utilities_impl.hpp diff --git a/sdk/third/websocketpp/logger/basic.hpp b/third/websocketpp/logger/basic.hpp similarity index 100% rename from sdk/third/websocketpp/logger/basic.hpp rename to third/websocketpp/logger/basic.hpp diff --git a/sdk/third/websocketpp/logger/levels.hpp b/third/websocketpp/logger/levels.hpp similarity index 100% rename from sdk/third/websocketpp/logger/levels.hpp rename to third/websocketpp/logger/levels.hpp diff --git a/sdk/third/websocketpp/logger/stub.hpp b/third/websocketpp/logger/stub.hpp similarity index 100% rename from sdk/third/websocketpp/logger/stub.hpp rename to third/websocketpp/logger/stub.hpp diff --git a/sdk/third/websocketpp/logger/syslog.hpp b/third/websocketpp/logger/syslog.hpp similarity index 100% rename from sdk/third/websocketpp/logger/syslog.hpp rename to third/websocketpp/logger/syslog.hpp diff --git a/sdk/third/websocketpp/message_buffer/alloc.hpp b/third/websocketpp/message_buffer/alloc.hpp similarity index 100% rename from sdk/third/websocketpp/message_buffer/alloc.hpp rename to third/websocketpp/message_buffer/alloc.hpp diff --git a/sdk/third/websocketpp/message_buffer/message.hpp b/third/websocketpp/message_buffer/message.hpp similarity index 100% rename from sdk/third/websocketpp/message_buffer/message.hpp rename to third/websocketpp/message_buffer/message.hpp diff --git a/sdk/third/websocketpp/message_buffer/pool.hpp b/third/websocketpp/message_buffer/pool.hpp similarity index 100% rename from sdk/third/websocketpp/message_buffer/pool.hpp rename to third/websocketpp/message_buffer/pool.hpp diff --git a/sdk/third/websocketpp/processors/base.hpp b/third/websocketpp/processors/base.hpp similarity index 100% rename from sdk/third/websocketpp/processors/base.hpp rename to third/websocketpp/processors/base.hpp diff --git a/sdk/third/websocketpp/processors/hybi00.hpp b/third/websocketpp/processors/hybi00.hpp similarity index 100% rename from sdk/third/websocketpp/processors/hybi00.hpp rename to third/websocketpp/processors/hybi00.hpp diff --git a/sdk/third/websocketpp/processors/hybi07.hpp b/third/websocketpp/processors/hybi07.hpp similarity index 100% rename from sdk/third/websocketpp/processors/hybi07.hpp rename to third/websocketpp/processors/hybi07.hpp diff --git a/sdk/third/websocketpp/processors/hybi08.hpp b/third/websocketpp/processors/hybi08.hpp similarity index 100% rename from sdk/third/websocketpp/processors/hybi08.hpp rename to third/websocketpp/processors/hybi08.hpp diff --git a/sdk/third/websocketpp/processors/hybi13.hpp b/third/websocketpp/processors/hybi13.hpp similarity index 100% rename from sdk/third/websocketpp/processors/hybi13.hpp rename to third/websocketpp/processors/hybi13.hpp diff --git a/sdk/third/websocketpp/processors/processor.hpp b/third/websocketpp/processors/processor.hpp similarity index 100% rename from sdk/third/websocketpp/processors/processor.hpp rename to third/websocketpp/processors/processor.hpp diff --git a/sdk/third/websocketpp/random/none.hpp b/third/websocketpp/random/none.hpp similarity index 100% rename from sdk/third/websocketpp/random/none.hpp rename to third/websocketpp/random/none.hpp diff --git a/sdk/third/websocketpp/random/random_device.hpp b/third/websocketpp/random/random_device.hpp similarity index 100% rename from sdk/third/websocketpp/random/random_device.hpp rename to third/websocketpp/random/random_device.hpp diff --git a/sdk/third/websocketpp/roles/client_endpoint.hpp b/third/websocketpp/roles/client_endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/roles/client_endpoint.hpp rename to third/websocketpp/roles/client_endpoint.hpp diff --git a/sdk/third/websocketpp/roles/server_endpoint.hpp b/third/websocketpp/roles/server_endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/roles/server_endpoint.hpp rename to third/websocketpp/roles/server_endpoint.hpp diff --git a/sdk/third/websocketpp/server.hpp b/third/websocketpp/server.hpp similarity index 100% rename from sdk/third/websocketpp/server.hpp rename to third/websocketpp/server.hpp diff --git a/sdk/third/websocketpp/sha1/sha1.hpp b/third/websocketpp/sha1/sha1.hpp similarity index 100% rename from sdk/third/websocketpp/sha1/sha1.hpp rename to third/websocketpp/sha1/sha1.hpp diff --git a/sdk/third/websocketpp/transport/asio/base.hpp b/third/websocketpp/transport/asio/base.hpp similarity index 100% rename from sdk/third/websocketpp/transport/asio/base.hpp rename to third/websocketpp/transport/asio/base.hpp diff --git a/sdk/third/websocketpp/transport/asio/connection.hpp b/third/websocketpp/transport/asio/connection.hpp similarity index 100% rename from sdk/third/websocketpp/transport/asio/connection.hpp rename to third/websocketpp/transport/asio/connection.hpp diff --git a/sdk/third/websocketpp/transport/asio/endpoint.hpp b/third/websocketpp/transport/asio/endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/transport/asio/endpoint.hpp rename to third/websocketpp/transport/asio/endpoint.hpp diff --git a/sdk/third/websocketpp/transport/asio/security/base.hpp b/third/websocketpp/transport/asio/security/base.hpp similarity index 100% rename from sdk/third/websocketpp/transport/asio/security/base.hpp rename to third/websocketpp/transport/asio/security/base.hpp diff --git a/sdk/third/websocketpp/transport/asio/security/none.hpp b/third/websocketpp/transport/asio/security/none.hpp similarity index 100% rename from sdk/third/websocketpp/transport/asio/security/none.hpp rename to third/websocketpp/transport/asio/security/none.hpp diff --git a/sdk/third/websocketpp/transport/asio/security/tls.hpp b/third/websocketpp/transport/asio/security/tls.hpp similarity index 100% rename from sdk/third/websocketpp/transport/asio/security/tls.hpp rename to third/websocketpp/transport/asio/security/tls.hpp diff --git a/sdk/third/websocketpp/transport/base/connection.hpp b/third/websocketpp/transport/base/connection.hpp similarity index 100% rename from sdk/third/websocketpp/transport/base/connection.hpp rename to third/websocketpp/transport/base/connection.hpp diff --git a/sdk/third/websocketpp/transport/base/endpoint.hpp b/third/websocketpp/transport/base/endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/transport/base/endpoint.hpp rename to third/websocketpp/transport/base/endpoint.hpp diff --git a/sdk/third/websocketpp/transport/debug/base.hpp b/third/websocketpp/transport/debug/base.hpp similarity index 100% rename from sdk/third/websocketpp/transport/debug/base.hpp rename to third/websocketpp/transport/debug/base.hpp diff --git a/sdk/third/websocketpp/transport/debug/connection.hpp b/third/websocketpp/transport/debug/connection.hpp similarity index 100% rename from sdk/third/websocketpp/transport/debug/connection.hpp rename to third/websocketpp/transport/debug/connection.hpp diff --git a/sdk/third/websocketpp/transport/debug/endpoint.hpp b/third/websocketpp/transport/debug/endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/transport/debug/endpoint.hpp rename to third/websocketpp/transport/debug/endpoint.hpp diff --git a/sdk/third/websocketpp/transport/iostream/base.hpp b/third/websocketpp/transport/iostream/base.hpp similarity index 100% rename from sdk/third/websocketpp/transport/iostream/base.hpp rename to third/websocketpp/transport/iostream/base.hpp diff --git a/sdk/third/websocketpp/transport/iostream/connection.hpp b/third/websocketpp/transport/iostream/connection.hpp similarity index 100% rename from sdk/third/websocketpp/transport/iostream/connection.hpp rename to third/websocketpp/transport/iostream/connection.hpp diff --git a/sdk/third/websocketpp/transport/iostream/endpoint.hpp b/third/websocketpp/transport/iostream/endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/transport/iostream/endpoint.hpp rename to third/websocketpp/transport/iostream/endpoint.hpp diff --git a/sdk/third/websocketpp/transport/stub/base.hpp b/third/websocketpp/transport/stub/base.hpp similarity index 100% rename from sdk/third/websocketpp/transport/stub/base.hpp rename to third/websocketpp/transport/stub/base.hpp diff --git a/sdk/third/websocketpp/transport/stub/connection.hpp b/third/websocketpp/transport/stub/connection.hpp similarity index 100% rename from sdk/third/websocketpp/transport/stub/connection.hpp rename to third/websocketpp/transport/stub/connection.hpp diff --git a/sdk/third/websocketpp/transport/stub/endpoint.hpp b/third/websocketpp/transport/stub/endpoint.hpp similarity index 100% rename from sdk/third/websocketpp/transport/stub/endpoint.hpp rename to third/websocketpp/transport/stub/endpoint.hpp diff --git a/sdk/third/websocketpp/uri.hpp b/third/websocketpp/uri.hpp similarity index 100% rename from sdk/third/websocketpp/uri.hpp rename to third/websocketpp/uri.hpp diff --git a/sdk/third/websocketpp/utf8_validator.hpp b/third/websocketpp/utf8_validator.hpp similarity index 100% rename from sdk/third/websocketpp/utf8_validator.hpp rename to third/websocketpp/utf8_validator.hpp diff --git a/sdk/third/websocketpp/utilities.hpp b/third/websocketpp/utilities.hpp similarity index 100% rename from sdk/third/websocketpp/utilities.hpp rename to third/websocketpp/utilities.hpp diff --git a/sdk/third/websocketpp/version.hpp b/third/websocketpp/version.hpp similarity index 100% rename from sdk/third/websocketpp/version.hpp rename to third/websocketpp/version.hpp