From 0c78b9663ec669272209f32b4506191839c37228 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Fri, 23 Jun 2023 12:04:20 -0500 Subject: [PATCH] Generate messages in downstream builds (#339) Expose message generation functionality to downstream packages and remove message generation from the msgs package. This new approach will now distribute the proto files, but will no longer distribute a binary library that downstream users will link against. Instead, downstream users can generate the messages that they need themselves or add new message definitions in their own packages. A summary of the changes required to make this happen: * Expose the mechanisms we use for message generation * This requires installing the protoc generator as well as our python script. * Add cmake functionality to let downstream users discover available messages and retrieve the installation path of the generator and python script (handled via cmake extras) * Create a core library that has the gz-msgs functionality minus the generated code. * Create a compiled library that maintains the CLI functionality. * Make conversions a header-only operation, so that the core library doesn't need to depend on the generated messages. Signed-off-by: Michael Carroll Co-authored-by: Ian Chen Co-authored-by: Addisu Z. Taddese --- CMakeLists.txt | 21 +- Migration.md | 10 + cmake/gz_msgs_factory.cmake | 71 + cmake/gz_msgs_generate.cmake | 127 ++ cmake/gz_msgs_protoc.cmake | 108 ++ cmake/gz_msgs_string_utils.cmake | 54 + cmake/target_link_messages.cmake | 58 + compiled/CMakeLists.txt | 71 + {src => compiled/include/gz/msgs}/gz.hh | 8 +- {src => compiled/src}/Factory_TEST.cc | 18 +- .../src}/PointCloudPackedUtils_TEST.cc | 11 - {src => compiled/src}/Utility_TEST.cc | 15 +- {src => compiled/src}/cmd/CMakeLists.txt | 4 +- {src => compiled/src}/cmd/cmdmsgs.rb.in | 0 .../src}/cmd/msgs.bash_completion.sh | 0 {src => compiled/src}/gz.cc | 13 +- core/CMakeLists.txt | 56 + {src => core/generator}/Generator.cc | 41 +- {src => core/generator}/Generator.hh | 0 {src => core/generator}/generator_main.cc | 0 .../include}/gz/msgs/CMakeLists.txt | 0 core/include/gz/msgs/Factory.hh | 122 ++ core/include/gz/msgs/MessageFactory.hh | 121 ++ .../include}/gz/msgs/PointCloudPackedUtils.hh | 82 + core/include/gz/msgs/Utility.hh | 38 + .../include}/gz/msgs/config.hh.in | 0 .../include/gz/msgs/convert/AxisAlignedBox.hh | 63 + core/include/gz/msgs/convert/Color.hh | 60 + core/include/gz/msgs/convert/DiscoveryType.hh | 122 ++ core/include/gz/msgs/convert/FuelMetadata.hh | 258 ++++ core/include/gz/msgs/convert/GeometryType.hh | 156 ++ core/include/gz/msgs/convert/Inertial.hh | 171 +++ core/include/gz/msgs/convert/JointType.hh | 147 ++ .../gz/msgs/convert/PixelFormatType.hh | 160 ++ core/include/gz/msgs/convert/Plane.hh | 67 + core/include/gz/msgs/convert/Pose.hh | 64 + core/include/gz/msgs/convert/Quaternion.hh | 60 + core/include/gz/msgs/convert/ShaderType.hh | 102 ++ .../gz/msgs/convert/SphericalCoordinates.hh | 118 ++ core/include/gz/msgs/convert/StdTypes.hh | 282 ++++ core/include/gz/msgs/convert/Vector2.hh | 57 + core/include/gz/msgs/convert/Vector3.hh | 58 + core/include/gz/msgs/convert/make_stubs.py | 119 ++ .../gz/msgs/detail/PointCloudPackedUtils.hh | 0 .../gz/msgs/detail/dynamic_message_cast.hh | 49 + core/src/DynamicFactory.cc | 144 ++ core/src/DynamicFactory.hh | 93 ++ core/src/Factory.cc | 62 + core/src/MessageFactory.cc | 118 ++ .../generating_custom_msgs/CMakeLists.txt | 52 + examples/generating_custom_msgs/README.md | 66 + examples/generating_custom_msgs/main.cc | 34 + .../proto/gz/custom_msgs/vector3d.proto | 32 +- examples/using_gz_msgs/CMakeLists.txt | 36 + examples/using_gz_msgs/README.md | 65 + examples/using_gz_msgs/main.cc | 40 + gz-msgs-extras.cmake.in | 78 + include/CMakeLists.txt | 1 - include/gz/CMakeLists.txt | 1 - include/gz/msgs/Factory.hh | 151 -- include/gz/msgs/Filesystem.hh | 93 -- include/gz/msgs/Utility.hh | 500 ------ proto/CMakeLists.txt | 2 +- src/CMakeLists.txt | 283 ---- src/Factory.cc | 318 ---- src/Filesystem.cc | 272 ---- src/Utility.cc | 1358 ----------------- test/integration/CMakeLists.txt | 7 +- tools/CMakeLists.txt | 8 + tools/gz_TEST.cc | 4 +- tools/gz_msgs_generate.py | 96 +- tools/gz_msgs_generate_factory.py | 175 +++ 72 files changed, 4131 insertions(+), 3120 deletions(-) create mode 100644 cmake/gz_msgs_factory.cmake create mode 100644 cmake/gz_msgs_generate.cmake create mode 100644 cmake/gz_msgs_protoc.cmake create mode 100644 cmake/gz_msgs_string_utils.cmake create mode 100644 cmake/target_link_messages.cmake create mode 100644 compiled/CMakeLists.txt rename {src => compiled/include/gz/msgs}/gz.hh (81%) rename {src => compiled/src}/Factory_TEST.cc (92%) rename {src => compiled/src}/PointCloudPackedUtils_TEST.cc (98%) rename {src => compiled/src}/Utility_TEST.cc (99%) rename {src => compiled/src}/cmd/CMakeLists.txt (94%) rename {src => compiled/src}/cmd/cmdmsgs.rb.in (100%) rename {src => compiled/src}/cmd/msgs.bash_completion.sh (100%) rename {src => compiled/src}/gz.cc (89%) create mode 100644 core/CMakeLists.txt rename {src => core/generator}/Generator.cc (83%) rename {src => core/generator}/Generator.hh (100%) rename {src => core/generator}/generator_main.cc (100%) rename {include => core/include}/gz/msgs/CMakeLists.txt (100%) create mode 100644 core/include/gz/msgs/Factory.hh create mode 100644 core/include/gz/msgs/MessageFactory.hh rename {include => core/include}/gz/msgs/PointCloudPackedUtils.hh (62%) create mode 100644 core/include/gz/msgs/Utility.hh rename {include => core/include}/gz/msgs/config.hh.in (100%) create mode 100644 core/include/gz/msgs/convert/AxisAlignedBox.hh create mode 100644 core/include/gz/msgs/convert/Color.hh create mode 100644 core/include/gz/msgs/convert/DiscoveryType.hh create mode 100644 core/include/gz/msgs/convert/FuelMetadata.hh create mode 100644 core/include/gz/msgs/convert/GeometryType.hh create mode 100644 core/include/gz/msgs/convert/Inertial.hh create mode 100644 core/include/gz/msgs/convert/JointType.hh create mode 100644 core/include/gz/msgs/convert/PixelFormatType.hh create mode 100644 core/include/gz/msgs/convert/Plane.hh create mode 100644 core/include/gz/msgs/convert/Pose.hh create mode 100644 core/include/gz/msgs/convert/Quaternion.hh create mode 100644 core/include/gz/msgs/convert/ShaderType.hh create mode 100644 core/include/gz/msgs/convert/SphericalCoordinates.hh create mode 100644 core/include/gz/msgs/convert/StdTypes.hh create mode 100644 core/include/gz/msgs/convert/Vector2.hh create mode 100644 core/include/gz/msgs/convert/Vector3.hh create mode 100755 core/include/gz/msgs/convert/make_stubs.py rename {include => core/include}/gz/msgs/detail/PointCloudPackedUtils.hh (100%) create mode 100644 core/include/gz/msgs/detail/dynamic_message_cast.hh create mode 100644 core/src/DynamicFactory.cc create mode 100644 core/src/DynamicFactory.hh create mode 100644 core/src/Factory.cc create mode 100644 core/src/MessageFactory.cc create mode 100644 examples/generating_custom_msgs/CMakeLists.txt create mode 100644 examples/generating_custom_msgs/README.md create mode 100644 examples/generating_custom_msgs/main.cc rename src/MessageTypes.hh.in => examples/generating_custom_msgs/proto/gz/custom_msgs/vector3d.proto (56%) create mode 100644 examples/using_gz_msgs/CMakeLists.txt create mode 100644 examples/using_gz_msgs/README.md create mode 100644 examples/using_gz_msgs/main.cc create mode 100644 gz-msgs-extras.cmake.in delete mode 100644 include/CMakeLists.txt delete mode 100644 include/gz/CMakeLists.txt delete mode 100644 include/gz/msgs/Factory.hh delete mode 100644 include/gz/msgs/Filesystem.hh delete mode 100644 include/gz/msgs/Utility.hh delete mode 100644 src/CMakeLists.txt delete mode 100644 src/Factory.cc delete mode 100644 src/Filesystem.cc delete mode 100644 src/Utility.cc create mode 100755 tools/gz_msgs_generate_factory.py diff --git a/CMakeLists.txt b/CMakeLists.txt index 4a20d41e..32669c2a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,13 +17,14 @@ find_package(gz-cmake3 REQUIRED) set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) -gz_configure_project(VERSION_SUFFIX) +gz_configure_project(VERSION_SUFFIX + CONFIG_EXTRAS "gz-msgs-extras.cmake.in") -if (UNIX AND NOT APPLE) - set (EXTRA_TEST_LIB_DEPS stdc++fs) -else() - set (EXTRA_TEST_LIB_DEPS) -endif() +# Install cmake support files +install( + DIRECTORY cmake/ + DESTINATION "lib/cmake/${PROJECT_NAME}" +) #============================================================================ # Set project-specific options @@ -71,6 +72,11 @@ gz_find_package(GzProtobuf COMPONENTS all PRETTY Protobuf) +#-------------------------------------- +# Find gz-utils +gz_find_package(gz-utils2 REQUIRED) +set(GZ_UTILS_VER ${gz-utils2_VERSION_MAJOR}) + #-------------------------------------- # Find gz-math gz_find_package(gz-math7 REQUIRED) @@ -90,7 +96,7 @@ gz_find_package(TINYXML2 REQUIRED PRIVATE PRETTY tinyxml2) #============================================================================ # Configure the build #============================================================================ -gz_configure_build(QUIT_IF_BUILD_ERRORS) +gz_configure_build(QUIT_IF_BUILD_ERRORS COMPONENTS compiled) #============================================================================ # gz command line support @@ -126,7 +132,6 @@ configure_file(${CMAKE_SOURCE_DIR}/tutorials.md.in ${CMAKE_BINARY_DIR}/tutorials gz_create_docs( API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md" TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md" - AUTOGENERATED_DOC "${CMAKE_BINARY_DIR}/include/gz/msgs/details" TAGFILES "${GZ-MATH_DOXYGEN_TAGFILE} = ${GZ-MATH_API_URL}" ) diff --git a/Migration.md b/Migration.md index 14291916..a410e50e 100644 --- a/Migration.md +++ b/Migration.md @@ -5,6 +5,16 @@ Deprecated code produces compile-time warnings. These warning serve as notification to users that their code should be upgraded. The next major release will remove the deprecated code. +## Gazebo Msgs 9.X to 10.X + +### Breaking changes + +1. The way that messages are included by downstream projects has been changed. + The messages package will now only install `.proto` files, and it is the responsibility of downstream + users of the msgs library to generate corresponding headers and source files via cmake macros. + * For more information, consult the `using_gz_msgs` example. + * Note that there will no longer be Ruby generated messages, this support will be restored as-needed. + ## Gazebo Msgs 8.X to 9.X 1. **SuppressWarnings.hh** is deprecated and isn't part of `msgs.hh` anymore. diff --git a/cmake/gz_msgs_factory.cmake b/cmake/gz_msgs_factory.cmake new file mode 100644 index 00000000..b86b1b4f --- /dev/null +++ b/cmake/gz_msgs_factory.cmake @@ -0,0 +1,71 @@ +################################################## +# A function that generates factory methods for generated gz-msgs +# The output of this is are a header and source file that can be used as part of your library +# for the gz::msgs::Factory +# Options: +# One value arguments: +# FACTORY_GEN_SCRIPT - Location of the factory generator script +# PROTO_PACKAGE - Protobuf package the file belongs to (e.g. "gz.msgs") +# PROTOC_EXEC - Path to protoc +# OUTPUT_CPP_DIR - Path where C++ files are saved +# OUTPUT_CPP_HH_VAR - A CMake variable name containing a list that the C++ headers should be appended to +# OUTPUT_CPP_CC_VAR - A Cmake variable name containing a list that the C++ sources should be appended to +# Multi value arguments +# INPUT_PROTOS - List of input proto files +# PROTO_PATH - Base directory of the proto files +function(gz_msgs_factory) + set(options "") + set(oneValueArgs + FACTORY_GEN_SCRIPT + PROTO_PACKAGE + OUTPUT_CPP_DIR + OUTPUT_CPP_HH_VAR + OUTPUT_CPP_CC_VAR) + set(multiValueArgs INPUT_PROTOS PROTO_PATH) + + cmake_parse_arguments(gz_msgs_factory "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) + + _gz_msgs_proto_pkg_to_path(${gz_msgs_factory_PROTO_PACKAGE} proto_package_dir) + + set(output_header "${gz_msgs_factory_OUTPUT_CPP_DIR}/${proto_package_dir}/MessageTypes.hh") + set(output_source "${gz_msgs_factory_OUTPUT_CPP_DIR}/${proto_package_dir}/register.cc") + + list(APPEND ${gz_msgs_factory_OUTPUT_CPP_HH_VAR} ${output_header}) + list(APPEND ${gz_msgs_factory_OUTPUT_CPP_CC_VAR} ${output_source}) + + list(APPEND output_files ${output_header}) + list(APPEND output_files ${output_source}) + + set(${gz_msgs_factory_OUTPUT_CPP_HH_VAR} ${${gz_msgs_factory_OUTPUT_CPP_HH_VAR}} PARENT_SCOPE) + set(${gz_msgs_factory_OUTPUT_CPP_CC_VAR} ${${gz_msgs_factory_OUTPUT_CPP_CC_VAR}} PARENT_SCOPE) + + set(depends_index) + # Full path to an index file, which contains all defined message types for that proto file + foreach(proto_file ${gz_msgs_factory_INPUT_PROTOS}) + # Get a unique path (gz.msgs.foo -> gz_msgs_foo) for naming the index + _gz_msgs_proto_to_unique(${proto_file} ${gz_msgs_factory_PROTO_PACKAGE} UNIQUE_NAME) + set(input_index "${gz_msgs_factory_OUTPUT_CPP_DIR}/${UNIQUE_NAME}.pb_index") + list(APPEND depends_index ${input_index}) + endforeach() + + set(GENERATE_ARGS + --output-cpp-path "${gz_msgs_factory_OUTPUT_CPP_DIR}" + --proto-package "${gz_msgs_factory_PROTO_PACKAGE}" + --proto-path "${gz_msgs_factory_PROTO_PATH}" + --protos "${gz_msgs_factory_INPUT_PROTOS}" + ) + + add_custom_command( + OUTPUT ${output_files} + COMMAND Python3::Interpreter + ARGS ${gz_msgs_factory_FACTORY_GEN_SCRIPT} ${GENERATE_ARGS} + DEPENDS + ${depends_index} + # While the script is executed in the source directory, it does not write + # to the source tree. All outputs are stored in the build directory. + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} + COMMENT "Running factory generator" + VERBATIM + ) + +endfunction() diff --git a/cmake/gz_msgs_generate.cmake b/cmake/gz_msgs_generate.cmake new file mode 100644 index 00000000..427313f0 --- /dev/null +++ b/cmake/gz_msgs_generate.cmake @@ -0,0 +1,127 @@ +################################################## +# The implementation of gz_msgs_generate_messages +# Options: +# One value arguments: +# MSGS_GEN_SCRIPT - Location of the messge generator script +# FACTORY_GEN_SCRIPT - Location of the factory generator script +# GZ_PROTOC_PLUGIN - Location of the gazebo generator plugin +# PROTO_PATH - Base directory of the proto files +# PROTO_PACKAGE - Protobuf package the file belongs to (e.g. "gz.msgs") +# MSGS_LIB - gz-msgs library to link to +# TARGET - Target (static library) to create +# Multi value arguments +# INPUT_PROTOS - List of input proto files +# DEPENDENCIES - List of generated messages targets that these messages depend on +# Primarily used when generating new custom messages downstream +# that depend on gz-msgs +function(gz_msgs_generate_messages_impl) + set(options "") + set(oneValueArgs TARGET PROTO_PACKAGE MSGS_GEN_SCRIPT GZ_PROTOC_PLUGIN FACTORY_GEN_SCRIPT MSGS_LIB PROTO_PATH) + set(multiValueArgs INPUT_PROTOS DEPENDENCIES) + + cmake_parse_arguments(generate_messages "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) + _gz_msgs_proto_pkg_to_string(${generate_messages_PROTO_PACKAGE} gen_dir) + + # Extract dependency information from targets + set(depends_proto_paths) + set(depends_includes) + + foreach(dep ${generate_messages_DEPENDENCIES}) + get_target_property(dep_proto_path ${dep} PROTO_DIR) + get_target_property(dep_proto_include_path ${dep} PROTO_INCLUDE_DIR) + + list(APPEND depends_proto_paths ${dep_proto_path}) + list(APPEND depends_includes ${dep_proto_include_path}) + endforeach() + + foreach(proto_file ${generate_messages_INPUT_PROTOS}) + gz_msgs_protoc( + MSGS_GEN_SCRIPT + ${generate_messages_MSGS_GEN_SCRIPT} + PROTO_PACKAGE + ${generate_messages_PROTO_PACKAGE} + GENERATE_CPP + INPUT_PROTO + ${proto_file} + PROTOC_EXEC + protobuf::protoc + GZ_PROTOC_PLUGIN + ${generate_messages_GZ_PROTOC_PLUGIN} + OUTPUT_CPP_DIR + "${PROJECT_BINARY_DIR}/${gen_dir}_gen" + OUTPUT_INCLUDES + gen_includes + OUTPUT_CPP_HH_VAR + gen_headers + OUTPUT_DETAIL_CPP_HH_VAR + gen_detail_headers + OUTPUT_CPP_CC_VAR + gen_sources + PROTO_PATH + ${generate_messages_PROTO_PATH} + DEPENDENCY_PROTO_PATHS + ${depends_proto_paths} + ) + endforeach() + + gz_msgs_factory( + FACTORY_GEN_SCRIPT + ${generate_messages_FACTORY_GEN_SCRIPT} + PROTO_PACKAGE + ${generate_messages_PROTO_PACKAGE} + INPUT_PROTOS + ${generate_messages_INPUT_PROTOS} + OUTPUT_CPP_DIR + "${PROJECT_BINARY_DIR}/${gen_dir}_gen" + OUTPUT_CPP_HH_VAR + gen_factory_headers + OUTPUT_CPP_CC_VAR + gen_factory_sources + PROTO_PATH + ${generate_messages_PROTO_PATH} + ) + + set_source_files_properties( + ${gen_headers} + ${gen_detail_headers} + ${gen_sources} + ${gen_factory_headers} + ${gen_factory_sources} + PROPERTIES GENERATED TRUE) + + if(WIN32) + set_source_files_properties(${gen_sources} + COMPILE_FLAGS "/wd4100 /wd4512 /wd4127 /wd4068 /wd4244 /wd4267 /wd4251 /wd4146") + endif() + + if(NOT MSVC) + # -Wno-switch-default flags is required for suppressing a warning in some of + # the generated protobuf files. + set_source_files_properties(${gen_sources} COMPILE_FLAGS "-Wno-switch-default -Wno-float-equal") + endif() + + add_library(${generate_messages_TARGET} STATIC ${gen_sources} ${gen_factory_sources}) + + # Use position indepedent code (-fPIC), because this library may be linked + # into a shared library by the consumer + set_property(TARGET ${generate_messages_TARGET} PROPERTY POSITION_INDEPENDENT_CODE ON) + + # Export the messages path and dependency messages paths for potential dependent message libs + set(PROTO_DIR) + list(APPEND PROTO_DIR ${generate_messages_PROTO_PATH}) + list(APPEND PROTO_DIR ${depends_proto_paths}) + + set(PROTO_INCLUDE_DIR) + list(APPEND PROTO_INCLUDE_DIR ${PROJECT_BINARY_DIR}/${gen_dir}_gen) + list(APPEND PROTO_INCLUDE_DIR ${depends_includes}) + + set_target_properties(${generate_messages_TARGET} PROPERTIES PROTO_DIR "${PROTO_DIR}") + set_target_properties(${generate_messages_TARGET} PROPERTIES PROTO_INCLUDE_DIR "${PROTO_INCLUDE_DIR}") + + foreach(dep ${generate_messages_DEPENDENCIES}) + add_dependencies(${generate_messages_TARGET} ${dep}) + endforeach() + + target_link_libraries(${generate_messages_TARGET} PUBLIC protobuf::libprotobuf ${generate_messages_MSGS_LIB}) + target_include_directories(${generate_messages_TARGET} PUBLIC ${PROJECT_BINARY_DIR}/${gen_dir}_gen ${depends_includes}) +endfunction() diff --git a/cmake/gz_msgs_protoc.cmake b/cmake/gz_msgs_protoc.cmake new file mode 100644 index 00000000..065803c2 --- /dev/null +++ b/cmake/gz_msgs_protoc.cmake @@ -0,0 +1,108 @@ +################################################## +# A function that calls protoc on a protobuf file +# Options: +# GENERATE_CPP - generates c++ code for the message if specified +# One value arguments: +# MSGS_GEN_SCRIPT - Path to the message generation python script +# PROTO_PACKAGE - Protobuf package the file belongs to (e.g. "gz.msgs") +# PROTOC_EXEC - Path to protoc +# GZ_PROTOC_PLUGIN - Path to the gazebo-specific protobuf compiler executable +# INPUT_PROTO - Path to the input .proto file +# OUTPUT_CPP_DIR - Path where C++ files are saved +# OUTPUT_INCLUDES - A CMake variable name containing a list that the C++ header path should be appended to +# OUTPUT_CPP_HH_VAR - A CMake variable name containing a list generated headers should be appended to +# OUTPUT_DETAIL_CPP_HH_VAR - A CMake variable name containing a list that the C++ detail headers should be appended to +# OUTPUT_CPP_CC_VAR - A Cmake variable name containing a list that the C++ source files should be appended to +# Multi value arguments +# PROTO_PATH - Passed to protoc --proto_path +# DEPENDENCY_PROTO_PATHS - Passed to protoc --proto_path +function(gz_msgs_protoc) + set(options GENERATE_CPP) + set(oneValueArgs + MSGS_GEN_SCRIPT + PROTO_PACKAGE + PROTOC_EXEC + GZ_PROTOC_PLUGIN + INPUT_PROTO + OUTPUT_CPP_DIR + OUTPUT_INCLUDES + OUTPUT_CPP_HH_VAR + OUTPUT_DETAIL_CPP_HH_VAR + OUTPUT_CPP_CC_VAR) + set(multiValueArgs PROTO_PATH DEPENDENCY_PROTO_PATHS) + + cmake_parse_arguments(gz_msgs_protoc "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) + + get_filename_component(ABS_FIL ${gz_msgs_protoc_INPUT_PROTO} ABSOLUTE) + get_filename_component(FIL_WE ${gz_msgs_protoc_INPUT_PROTO} NAME_WE) + + set(protoc_args) + set(output_files) + + _gz_msgs_proto_pkg_to_path(${gz_msgs_protoc_PROTO_PACKAGE} proto_package_dir) + + if(gz_msgs_protoc_GENERATE_CPP) + # Full path to gazeob-specific header (${PROJECT_BINARY_DIR}/include/gz/msgs/foo.pb.h) + set(output_header "${gz_msgs_protoc_OUTPUT_CPP_DIR}/${proto_package_dir}/${FIL_WE}.pb.h") + # Full path to generated protobuf header (${PROJECT_BINARY_DIR}/include/gz/msgs/details/foo.pb.h) + set(output_detail_header "${gz_msgs_protoc_OUTPUT_CPP_DIR}/${proto_package_dir}/details/${FIL_WE}.pb.h") + # Full path to generated protobuf source (${PROJECT_BINARY_DIR}/include/foo.pb.cc) + set(output_source "${gz_msgs_protoc_OUTPUT_CPP_DIR}/${proto_package_dir}/${FIL_WE}.pb.cc") + + _gz_msgs_proto_to_unique(${gz_msgs_protoc_INPUT_PROTO} ${gz_msgs_protoc_PROTO_PACKAGE} UNIQUE_NAME) + + # Full path to an index file, which contains all defined message types for that proto file + set(output_index "${gz_msgs_protoc_OUTPUT_CPP_DIR}/${UNIQUE_NAME}.pb_index") + + # Generate a clean relative path (gz/msgs/foo.pb.h) + string(REPLACE "${PROJECT_BINARY_DIR}/include/" "" output_include ${output_header}) + list(APPEND ${gz_msgs_protoc_OUTPUT_INCLUDES} "${output_include}") + + list(APPEND ${gz_msgs_protoc_OUTPUT_CPP_HH_VAR} ${output_header}) + list(APPEND ${gz_msgs_protoc_OUTPUT_CPP_CC_VAR} ${output_source}) + list(APPEND ${gz_msgs_protoc_OUTPUT_DETAIL_CPP_HH_VAR} ${output_detail_header}) + + list(APPEND output_files ${output_header}) + list(APPEND output_files ${output_detail_header}) + list(APPEND output_files ${output_source}) + list(APPEND output_files ${output_index}) + + set(${gz_msgs_protoc_OUTPUT_INCLUDES} ${${gz_msgs_protoc_OUTPUT_INCLUDES}} PARENT_SCOPE) + set(${gz_msgs_protoc_OUTPUT_DETAIL_CPP_HH_VAR} ${${gz_msgs_protoc_OUTPUT_DETAIL_CPP_HH_VAR}} PARENT_SCOPE) + set(${gz_msgs_protoc_OUTPUT_CPP_HH_VAR} ${${gz_msgs_protoc_OUTPUT_CPP_HH_VAR}} PARENT_SCOPE) + set(${gz_msgs_protoc_OUTPUT_CPP_CC_VAR} ${${gz_msgs_protoc_OUTPUT_CPP_CC_VAR}} PARENT_SCOPE) + endif() + + set(GENERATE_ARGS + --protoc-exec "$" + --gz-generator-bin "${gz_msgs_protoc_GZ_PROTOC_PLUGIN}" + --proto-path "${gz_msgs_protoc_PROTO_PATH}" + --input-path "${ABS_FIL}" + ) + + if(gz_msgs_protoc_DEPENDENCY_PROTO_PATHS) + list(APPEND GENERATE_ARGS + --dependency-proto-paths "${gz_msgs_protoc_DEPENDENCY_PROTO_PATHS}" + ) + endif() + + if(${gz_msgs_protoc_GENERATE_CPP}) + list(APPEND GENERATE_ARGS + --generate-cpp + --output-cpp-path "${gz_msgs_protoc_OUTPUT_CPP_DIR}") + endif() + + add_custom_command( + OUTPUT ${output_files} + COMMAND Python3::Interpreter + ARGS ${gz_msgs_protoc_MSGS_GEN_SCRIPT} ${GENERATE_ARGS} + DEPENDS + ${ABS_FIL} + # While the script is executed in the source directory, it does not write + # to the source tree. All outputs are stored in the build directory. + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} + COMMENT "Running protoc on ${gz_msgs_protoc_INPUT_PROTO}" + VERBATIM + ) + +endfunction() diff --git a/cmake/gz_msgs_string_utils.cmake b/cmake/gz_msgs_string_utils.cmake new file mode 100644 index 00000000..21397dc6 --- /dev/null +++ b/cmake/gz_msgs_string_utils.cmake @@ -0,0 +1,54 @@ +# Copyright 2023 Open Source Robotics Foundation, Inc. +# +# 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. + +################################################## +# A function that converts proto package into a filesystem path +# (e.g. gz.msgs -> gz/msgs) +# Arguments: +# PROTO_PACKAGE - Input package name to convert to path +# PROTO_PACKAGE_PATH - Output formatted path +function(_gz_msgs_proto_pkg_to_path PROTO_PACKAGE PROTO_PACKAGE_PATH) + if (PROTO_PACKAGE) + string(REPLACE "." "/" PACKAGE_PATH ${PROTO_PACKAGE}) + else() + set(PACKAGE_PATH ".") + endif() + set(${PROTO_PACKAGE_PATH} ${PACKAGE_PATH} PARENT_SCOPE) +endfunction() + +################################################## +# A function that converts proto package into a string with underscores +# (e.g. gz.msgs -> gz_msgs) +# Arguments: +# PROTO_PACKAGE - Input package name to convert to path +# PROTO_PACKAGE_PATH - Output formatted path +function(_gz_msgs_proto_pkg_to_string PROTO_PACKAGE PROTO_PACKAGE_STRING) + string(REPLACE "." "_" PACKAGE_STRING ${PROTO_PACKAGE}) + set(${PROTO_PACKAGE_STRING} ${PACKAGE_STRING} PARENT_SCOPE) +endfunction() + + +################################################## +# A function that converts a proto file and package into a unique string +# (e.g. gz.msgs.foobar -> gz_msgs_foobar) +# Arguments: +# PROTO_FILE - Input Full path to proto file +# PROTO_PACKAGE - Input proto package name +# UNIQUE_NAME - Output unique name +function(_gz_msgs_proto_to_unique PROTO_FILE PROTO_PACKAGE UNIQUE_NAME) + # Get the filename without extension or directory + get_filename_component(FIL_WE ${PROTO_FILE} NAME_WE) + _gz_msgs_proto_pkg_to_string(${PROTO_PACKAGE} PROTO_PACKAGE_STRING) + set(${UNIQUE_NAME} "${PROTO_PACKAGE_STRING}_${FIL_WE}" PARENT_SCOPE) +endfunction() diff --git a/cmake/target_link_messages.cmake b/cmake/target_link_messages.cmake new file mode 100644 index 00000000..97682ac2 --- /dev/null +++ b/cmake/target_link_messages.cmake @@ -0,0 +1,58 @@ +# Copyright 2023 Open Source Robotics Foundation, Inc. +# +# 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. + +################################################## +# A function that does whole-archive linking for messages +# This is only required in the case that the static initialization based +# factory registration is needed. Whole archive linking guarantees that the +# messages are correctly registered with the factory. +# Alternatively, use the `RegisterAll` generated method to manually register. +# One value arguments: +# TARGET - Target to link MSGS_TARGETS messages into +# Multi value arguments +# MSGS_TARGETS - List of generated messages targets to link into TARGET +function(target_link_messages) + set(options) + set(oneValueArgs TARGET) + set(multiValueArgs MSG_TARGETS) + + cmake_parse_arguments(target_link_messages "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) + + foreach(message_lib ${target_link_messages_MSG_TARGETS}) + if (CMAKE_CXX_COMPILER_ID STREQUAL "MSVC") + # MSVC link flag doesn't work with generator expressions + # TODO(mjcarroll) When CMake 3.24 is genrally available, use + # linking generator expressions as described here: + # https://cmake.org/cmake/help/latest/manual/cmake-generator-expressions.7.html#genex:LINK_LIBRARY + target_link_libraries(${target_link_messages_TARGET} -WHOLEARCHIVE:$) + + else() + target_link_libraries(${target_link_messages_TARGET} + $<$:-Wl,--whole-archive> + $<$:-force_load> + $<$:-force_load> ${message_lib} + $<$:-Wl,--no-whole-archive>) + endif() + + # Explicitly add dependency, link libraries, and includes as the WHOLEARCHIVE flag doesn't + # do that on Windows. + add_dependencies(${target_link_messages_TARGET} ${message_lib}) + get_target_property(message_lib_INCLUDES ${message_lib} INTERFACE_INCLUDE_DIRECTORIES) + get_target_property(message_lib_LIBS ${message_lib} INTERFACE_LINK_LIBRARIES) + target_include_directories(${target_link_messages_TARGET} PRIVATE ${message_lib_INCLUDES}) + # Note: not using visibility here because it conflicts with gazebo-built tests that don't use + # any visiblity parameter + target_link_libraries(${target_link_messages_TARGET} ${message_lib_LIBS}) + endforeach() +endfunction() diff --git a/compiled/CMakeLists.txt b/compiled/CMakeLists.txt new file mode 100644 index 00000000..19e11021 --- /dev/null +++ b/compiled/CMakeLists.txt @@ -0,0 +1,71 @@ +include(${PROJECT_SOURCE_DIR}/cmake/gz_msgs_string_utils.cmake) +include(${PROJECT_SOURCE_DIR}/cmake/gz_msgs_factory.cmake) +include(${PROJECT_SOURCE_DIR}/cmake/gz_msgs_generate.cmake) +include(${PROJECT_SOURCE_DIR}/cmake/gz_msgs_protoc.cmake) +include(${PROJECT_SOURCE_DIR}/cmake/target_link_messages.cmake) + +file (GLOB proto_files ${PROJECT_SOURCE_DIR}/proto/gz/msgs/*.proto) + +# Using the impl, rather than the extras function because we are building in-source +gz_msgs_generate_messages_impl( + MSGS_GEN_SCRIPT + ${PROJECT_SOURCE_DIR}/tools/gz_msgs_generate.py + FACTORY_GEN_SCRIPT + ${PROJECT_SOURCE_DIR}/tools/gz_msgs_generate_factory.py + GZ_PROTOC_PLUGIN + $ + INPUT_PROTOS + ${proto_files} + PROTO_PACKAGE + "gz.msgs" + PROTO_PATH + ${PROJECT_SOURCE_DIR}/proto + MSGS_LIB + gz-msgs${PROJECT_VERSION_MAJOR} + TARGET + gz_msgs_msgs +) + +gz_add_component(compiled + SOURCES src/gz.cc + GET_TARGET_NAME compiled_target) + +# Not using target_link_messages because we are registering messages in gz.cc +target_link_libraries(${compiled_target} PRIVATE gz_msgs_msgs) +target_include_directories(${compiled_target} PRIVATE include) + +install( + DIRECTORY include/ + DESTINATION ${GZ_INCLUDE_INSTALL_DIR_FULL}) + +################################################## +# Build unit tests +gz_get_libsources_and_unittests(sources gtest_sources) + +# Build the unit tests. +gz_build_tests(TYPE UNIT + SOURCES + ${gtest_sources} + LIB_DEPS + TINYXML2::TINYXML2 +) + +if (TARGET UNIT_Factory_TEST) + target_compile_definitions(UNIT_Factory_TEST + PRIVATE GZ_MSGS_TEST_PATH="${PROJECT_SOURCE_DIR}/test") + target_link_messages(TARGET UNIT_Factory_TEST MSG_TARGETS gz_msgs_msgs) +endif() + +if (TARGET UNIT_Utility_TEST) + target_link_messages(TARGET UNIT_Utility_TEST MSG_TARGETS gz_msgs_msgs) +endif() + +if (TARGET UNIT_PointCloudPackedUtils_TEST) + target_link_messages(TARGET UNIT_PointCloudPackedUtils_TEST MSG_TARGETS gz_msgs_msgs) +endif() + +################################################## +# gz msgs command +if(NOT WIN32) + add_subdirectory(src/cmd) +endif() diff --git a/src/gz.hh b/compiled/include/gz/msgs/gz.hh similarity index 81% rename from src/gz.hh rename to compiled/include/gz/msgs/gz.hh index f5c51852..3a91a875 100644 --- a/src/gz.hh +++ b/compiled/include/gz/msgs/gz.hh @@ -19,17 +19,17 @@ #define GZ_MSGS_GZ_HH_ #include -#include "gz/msgs/Export.hh" +#include "gz/msgs/compiled/Export.hh" /// \brief External hook to execute 'gz msg -i' from the command line. /// \param[in] _msg Message type name. -extern "C" GZ_MSGS_VISIBLE void cmdMsgInfo(const char *_msg); +extern "C" GZ_MSGS_COMPILED_VISIBLE void cmdMsgInfo(const char *_msg); /// \brief External hook to execute 'gz msg -l' from the command line. -extern "C" GZ_MSGS_VISIBLE void cmdMsgList(); +extern "C" GZ_MSGS_COMPILED_VISIBLE void cmdMsgList(); /// \brief External hook to read the library version. /// \return C-string representing the version. Ex.: 0.1.2 -extern "C" GZ_MSGS_VISIBLE const char *gzMsgsVersion(); +extern "C" GZ_MSGS_COMPILED_VISIBLE const char *gzMsgsVersion(); #endif diff --git a/src/Factory_TEST.cc b/compiled/src/Factory_TEST.cc similarity index 92% rename from src/Factory_TEST.cc rename to compiled/src/Factory_TEST.cc index 82b9bb77..63cabc33 100644 --- a/src/Factory_TEST.cc +++ b/compiled/src/Factory_TEST.cc @@ -27,8 +27,16 @@ using namespace gz; +namespace { static constexpr const char * kMsgsTestPath = GZ_MSGS_TEST_PATH; +#ifdef _WIN32 +static constexpr char kEnvironmentVariableSeparator = ';'; +#else +static constexpr char kEnvironmentVariableSeparator = ':'; +#endif +} // namespace + ///////////////////////////////////////////////// TEST(FactoryTest, Type) { @@ -36,7 +44,7 @@ TEST(FactoryTest, Type) msgs::Factory::Types(types); EXPECT_FALSE(types.empty()); EXPECT_TRUE(std::find(types.begin(), types.end(), - std::string("gz_msgs.Vector3d")) != + std::string("gz.msgs.Vector3d")) != types.end()); } @@ -76,7 +84,7 @@ TEST(FactoryTest, NewDynamicFactory) std::filesystem::path test_path(kMsgsTestPath); paths += (test_path / "desc").string(); - paths += ":"; + paths += kEnvironmentVariableSeparator; paths += test_path.string(); msgs::Factory::LoadDescriptors(paths); @@ -103,9 +111,9 @@ TEST(FactoryTest, MultipleMessagesInAProto) { auto typesInSameFile = { - "gz_msgs.SerializedEntityMap", - "gz_msgs.SerializedStateMap", - "gz_msgs.SerializedStepMap" + "gz.msgs.SerializedEntityMap", + "gz.msgs.SerializedStateMap", + "gz.msgs.SerializedStepMap" }; std::vector types; diff --git a/src/PointCloudPackedUtils_TEST.cc b/compiled/src/PointCloudPackedUtils_TEST.cc similarity index 98% rename from src/PointCloudPackedUtils_TEST.cc rename to compiled/src/PointCloudPackedUtils_TEST.cc index a488b0dc..9352758c 100644 --- a/src/PointCloudPackedUtils_TEST.cc +++ b/compiled/src/PointCloudPackedUtils_TEST.cc @@ -17,19 +17,9 @@ #include -// TODO(chapulina) Our headers shouldn't be leaking warnings from protobuf -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable: 4251) -#endif - #include "gz/msgs/PointCloudPackedUtils.hh" #include "gz/msgs/Utility.hh" -#ifdef _MSC_VER -#pragma warning(pop) -#endif - using namespace gz; using namespace msgs; @@ -326,4 +316,3 @@ TEST(PointCloudPackedUtilsTest, SizeOfPointField) EXPECT_EQ(4, sizeOfPointField(PointCloudPacked::Field::FLOAT32)); EXPECT_EQ(8, sizeOfPointField(PointCloudPacked::Field::FLOAT64)); } - diff --git a/src/Utility_TEST.cc b/compiled/src/Utility_TEST.cc similarity index 99% rename from src/Utility_TEST.cc rename to compiled/src/Utility_TEST.cc index a93d5363..353d7ced 100644 --- a/src/Utility_TEST.cc +++ b/compiled/src/Utility_TEST.cc @@ -19,8 +19,10 @@ #include #include -#include "gz/msgs/wrench.pb.h" #include "gz/msgs/Utility.hh" +#include "gz/msgs/PointCloudPackedUtils.hh" + +#include "gz/msgs/wrench.pb.h" using namespace gz; @@ -208,7 +210,7 @@ TEST(MsgsTest, ConvertMsgsInertialToMath) math::Vector3d(2, 3, 4), math::Vector3d(0.1, 0.2, 0.3)), pose)); - auto inertial = msgs::Convert(msg); + gz::math::Inertial inertial = msgs::Convert(msg); EXPECT_DOUBLE_EQ(12.0, inertial.MassMatrix().Mass()); EXPECT_DOUBLE_EQ(2.0, inertial.MassMatrix().Ixx()); @@ -319,7 +321,9 @@ TEST(MsgsTest, ConvertMathMassMatrix3ToMsgs) EXPECT_DOUBLE_EQ(0.1, msg.ixy()); EXPECT_DOUBLE_EQ(0.2, msg.ixz()); EXPECT_DOUBLE_EQ(0.3, msg.iyz()); - EXPECT_EQ(math::Pose3d::Zero, msgs::Convert(msg.pose())); + + auto convertedPose = msgs::Convert(msg.pose()); + EXPECT_TRUE(convertedPose.Equal(math::Pose3d::Zero, 1e-1)); } ///////////////////////////////////////////////// @@ -793,9 +797,12 @@ TEST(MsgsTest, SetSphericalCoordinates) TEST(MsgsTest, SetStringMsg) { msgs::StringMsg msg; - msgs::Set(&msg, "a string msg"); + msgs::Set(&msg, "a string msg"); EXPECT_EQ("a string msg", msg.data()); + + msgs::Set(&msg, std::string("a string msg2")); + EXPECT_EQ("a string msg2", msg.data()); } ///////////////////////////////////////////////// diff --git a/src/cmd/CMakeLists.txt b/compiled/src/cmd/CMakeLists.txt similarity index 94% rename from src/cmd/CMakeLists.txt rename to compiled/src/cmd/CMakeLists.txt index 3a746eb0..119bd9a8 100644 --- a/src/cmd/CMakeLists.txt +++ b/compiled/src/cmd/CMakeLists.txt @@ -7,7 +7,7 @@ set(cmd_script_configured_test "${cmd_script_generated_test}.configured") # Set the library_location variable to the full path of the library file within # the build directory. -set(library_location "$") +set(library_location "$") configure_file( "cmd${GZ_DESIGNATION}.rb.in" @@ -29,7 +29,7 @@ set(cmd_script_configured "${cmd_script_generated}.configured") # Set the library_location variable to the relative path to the library file # within the install directory structure. -set(library_location "../../../${CMAKE_INSTALL_LIBDIR}/$") +set(library_location "../../../${CMAKE_INSTALL_LIBDIR}/$") configure_file( "cmd${GZ_DESIGNATION}.rb.in" diff --git a/src/cmd/cmdmsgs.rb.in b/compiled/src/cmd/cmdmsgs.rb.in similarity index 100% rename from src/cmd/cmdmsgs.rb.in rename to compiled/src/cmd/cmdmsgs.rb.in diff --git a/src/cmd/msgs.bash_completion.sh b/compiled/src/cmd/msgs.bash_completion.sh similarity index 100% rename from src/cmd/msgs.bash_completion.sh rename to compiled/src/cmd/msgs.bash_completion.sh diff --git a/src/gz.cc b/compiled/src/gz.cc similarity index 89% rename from src/gz.cc rename to compiled/src/gz.cc index a3c1b736..7bb6d4fa 100644 --- a/src/gz.cc +++ b/compiled/src/gz.cc @@ -26,14 +26,15 @@ #pragma warning(pop) #endif -#include "gz.hh" - #include #include #include #include #include +#include + +#include #ifdef _MSC_VER # pragma warning(disable: 4503) @@ -43,9 +44,10 @@ using namespace gz; using namespace msgs; ////////////////////////////////////////////////// -extern "C" GZ_MSGS_VISIBLE +extern "C" GZ_MSGS_COMPILED_VISIBLE void cmdMsgInfo(const char *_msg) { + gz::msgs::RegisterAll(); if (_msg) { auto msg = Factory::New(_msg); @@ -68,9 +70,10 @@ void cmdMsgInfo(const char *_msg) } ////////////////////////////////////////////////// -extern "C" GZ_MSGS_VISIBLE +extern "C" GZ_MSGS_COMPILED_VISIBLE void cmdMsgList() { + gz::msgs::RegisterAll(); std::vector types; Factory::Types(types); @@ -79,7 +82,7 @@ void cmdMsgList() } ////////////////////////////////////////////////// -extern "C" GZ_MSGS_VISIBLE +extern "C" GZ_MSGS_COMPILED_VISIBLE const char *gzMsgsVersion() { return GZ_MSGS_VERSION_FULL; diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt new file mode 100644 index 00000000..d0f115ae --- /dev/null +++ b/core/CMakeLists.txt @@ -0,0 +1,56 @@ +################################################## +# Build a custom protoc plugin +set(PROTOC_PLUGIN ${PROJECT_NAME}_protoc_plugin) + +gz_add_executable(${PROTOC_PLUGIN} + generator/Generator.cc + generator/generator_main.cc) +target_link_libraries(${PROTOC_PLUGIN} + protobuf::libprotoc + protobuf::libprotobuf) +target_include_directories(${PROTOC_PLUGIN} PRIVATE ${PROTOBUF_INCLUDE_DIR}) +target_compile_features(${PROTOC_PLUGIN} PRIVATE ${GZ_CXX_11_FEATURES}) + +if (UNIX) + target_link_libraries(${PROTOC_PLUGIN} pthread) +endif() + +install(TARGETS ${PROTOC_PLUGIN} DESTINATION ${GZ_BIN_INSTALL_DIR}) + +################################################## +# Build core library +gz_get_libsources_and_unittests(sources gtest_sources) + +gz_create_core_library(SOURCES + src/Factory.cc + src/MessageFactory.cc + src/DynamicFactory.cc +) + +target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} + PUBLIC + protobuf::libprotobuf + gz-math${GZ_MATH_VER}::gz-math${GZ_MATH_VER} + PRIVATE + TINYXML2::TINYXML2 +) + +target_include_directories(${PROJECT_LIBRARY_TARGET_NAME} + SYSTEM PUBLIC $) + +if (CMAKE_CXX_COMPILER_ID MATCHES "Clang") + # Disable warning in generated *.pb.cc code + target_compile_options(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE -Wno-invalid-offsetof) +endif() + +################################################## +# Build unit tests +# Build the unit tests. +gz_build_tests(TYPE UNIT + SOURCES + ${gtest_sources} + LIB_DEPS + TINYXML2::TINYXML2 +) + +add_subdirectory(include/gz/msgs) diff --git a/src/Generator.cc b/core/generator/Generator.cc similarity index 83% rename from src/Generator.cc rename to core/generator/Generator.cc index afa3b0a8..6252bda0 100644 --- a/src/Generator.cc +++ b/core/generator/Generator.cc @@ -18,6 +18,7 @@ #include #include #include +#include #include #include #include @@ -89,7 +90,7 @@ bool Generator::Generate(const FileDescriptor *_file, auto parent_path = filePath.parent_path(); auto fileStem = filePath.stem().string(); - // protoc generates ignition/msgs/msg.pb.cc and ignition/msgs/msg.pb.hh + // protoc generates gz/msgs/msg.pb.cc and gz/msgs/msg.pb.hh // This generator injects code into the msg.pb.cc file, but generates // a completely new header that wraps the original protobuf header // @@ -112,6 +113,11 @@ bool Generator::Generate(const FileDescriptor *_file, newHeaderFilename += part.string() + "/"; sourceFilename += part.string() + "/"; } + + auto message_type_index = + _generatorContext->Open(identifier + fileStem + ".pb_index"); + io::Printer indexPrinter(message_type_index, '$'); + identifier += fileStem; headerFilename += fileStem + ".gz.h"; newHeaderFilename += "details/" + fileStem + ".pb.h"; @@ -136,15 +142,7 @@ bool Generator::Generate(const FileDescriptor *_file, #include -#include - -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable: 4100 4512 4127 4068 4244 4267 4251 4146) -#endif - #include <$detail_header$> - )"); auto ns = getNamespaces(_file->package()); @@ -157,6 +155,9 @@ bool Generator::Generate(const FileDescriptor *_file, auto desc = _file->message_type(i); std::string ptrTypes; + indexPrinter.PrintRaw(desc->name()); + indexPrinter.PrintRaw("\n"); + // Define std::unique_ptr types for our messages ptrTypes += "typedef std::unique_ptr<" + desc->name() + "> " @@ -185,33 +186,11 @@ bool Generator::Generate(const FileDescriptor *_file, printer.PrintRaw("} // namespace " + *name + "\n"); } - printer.PrintRaw("#ifdef _MSC_VER\n"); - printer.PrintRaw("#pragma warning(pop)\n"); - printer.PrintRaw("#endif\n"); printer.PrintRaw("\n"); printer.Print(variables, "#endif // $define_guard$\n"); } - // Inject code in the auto-generated source files immediately following - // the #include calls. - { - std::unique_ptr output( - _generatorContext->OpenForInsert(sourceFilename, "includes")); - io::Printer printer(output.get(), '$'); - - // Add the gz-msgs Factory header - printer.Print("#include \"gz/msgs/Factory.hh\"\n", "name", - "includes"); - - for (auto i = 0; i < _file->message_type_count(); ++i) - { - std::string factory = "GZ_REGISTER_STATIC_MSG(\"gz_msgs."; - factory += _file->message_type(i)->name() + "\", " + - _file->message_type(i)->name() +")\n"; - printer.Print(factory.c_str(), "name", "includes"); - } - } return true; } } diff --git a/src/Generator.hh b/core/generator/Generator.hh similarity index 100% rename from src/Generator.hh rename to core/generator/Generator.hh diff --git a/src/generator_main.cc b/core/generator/generator_main.cc similarity index 100% rename from src/generator_main.cc rename to core/generator/generator_main.cc diff --git a/include/gz/msgs/CMakeLists.txt b/core/include/gz/msgs/CMakeLists.txt similarity index 100% rename from include/gz/msgs/CMakeLists.txt rename to core/include/gz/msgs/CMakeLists.txt diff --git a/core/include/gz/msgs/Factory.hh b/core/include/gz/msgs/Factory.hh new file mode 100644 index 00000000..80607c1d --- /dev/null +++ b/core/include/gz/msgs/Factory.hh @@ -0,0 +1,122 @@ +/* + * Copyright (C) 2016 Open Source Robotics Foundation + * + * 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. + * +*/ +#ifndef GZ_MSGS_FACTORY_HH_ +#define GZ_MSGS_FACTORY_HH_ + +#include +#include +#include +#include + +#include "gz/msgs/config.hh" +#include "gz/msgs/Export.hh" + +#include "gz/msgs/MessageFactory.hh" + +namespace gz::msgs +{ + // Inline bracket to help doxygen filtering. + inline namespace GZ_MSGS_VERSION_NAMESPACE { + + /// \class Factory Factory.hh gz/msgs.hh + /// \brief A factory that generates protobuf message based on a string type. + /// This allows for global registration of messages via static initialization. + /// If you don't need the singleton, consider using MessageFactory instead + class GZ_MSGS_VISIBLE Factory + { + /// \brief Unique pointer to base message type + public: using MessagePtr = MessageFactory::MessagePtr; + + /// \brief Function that returns unique pointer to base message type + public: using FactoryFn = MessageFactory::FactoryFn; + + /// \brief A map of message types as strings to factory functions + public: using FactoryFnCollection = MessageFactory::FactoryFnCollection; + + /// \brief Private constuctor + private: Factory() = default; + + /// \brief Deleted copy constructor + public: Factory(const Factory&) = delete; + + /// \brief Deleted copy assignment + public: void operator=(const Factory&) = delete; + + /// \brief Deleted move constructor + public: Factory(Factory&&) = delete; + + /// \brief Deleted move assignment + public: void operator=(Factory&&) = delete; + + /// \brief Get the global MessageFactory instance + /// \return Reference to the global MessageFactory instance + public: static MessageFactory& Instance(); + + /// \brief Register a message. + /// \param[in] _msgType Type of message to register. + /// \param[in] _factoryfn Function that generates the message. + public: static void Register(const std::string &_msgType, + FactoryFn _factoryfn); + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: template + static std::unique_ptr New(const std::string &_msgType) + { + return Factory::Instance().New(_msgType); + } + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \param[in] _args Message arguments. This will populate the message. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: template + static std::unique_ptr New(const std::string &_msgType, + const std::string &_args) + { + return Factory::Instance().New(_msgType, _args); + } + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: static MessagePtr New(const std::string &_msgType); + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \param[in] _args Message arguments. This will populate the message. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: static MessagePtr + New(const std::string &_msgType, const std::string &_args); + + /// \brief Get all the message types + /// \param[out] _types Vector of strings of the message types. + public: static void Types(std::vector &_types); + + /// \brief Load a collection of descriptor .desc files. + /// \param[in] _paths A set of directories containing .desc decriptor + /// files. Each directory should be separated by ":". + public: static void LoadDescriptors(const std::string &_paths); + }; +} +} // namespace gz::msgs +#endif diff --git a/core/include/gz/msgs/MessageFactory.hh b/core/include/gz/msgs/MessageFactory.hh new file mode 100644 index 00000000..6bb0cd01 --- /dev/null +++ b/core/include/gz/msgs/MessageFactory.hh @@ -0,0 +1,121 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * +*/ +#ifndef GZ_MSGS_MESSAGE_FACTORY_HH_ +#define GZ_MSGS_MESSAGE_FACTORY_HH_ + +#include +#include +#include +#include +#include + +#include "gz/msgs/config.hh" +#include "gz/msgs/Export.hh" +#include "gz/msgs/detail/dynamic_message_cast.hh" +#include + +namespace gz::msgs { + /// Forward declarations + class DynamicFactory; + + // Inline bracket to help doxygen filtering. + inline namespace GZ_MSGS_VERSION_NAMESPACE { + + /// \class MessageFactory MessageFactory.hh + /// \brief A factory that generates protobuf message based on a string type. + /// This class will also try to load all Protobuf descriptors in paths + /// provided in LoadDescriptors as well as the GZ_DESCRIPTOR_PATH + /// environment variable. + class GZ_MSGS_VISIBLE MessageFactory + { + /// \brief Base message type + public: using Message = google::protobuf::Message; + + /// \brief Unique pointer to base message type + public: using MessagePtr = std::unique_ptr; + + /// \brief Function that returns unique pointer to base message type + public: using FactoryFn = std::function; + + /// \brief A map of message types as strings to factory functions + public: using FactoryFnCollection = std::map; + + /// \brief Constructor + public: MessageFactory(); + + /// \brief Destructor + public: ~MessageFactory(); + + /// \brief Register a message. + /// \param[in] _msgType Type of message to register. + /// \param[in] _factoryFn Function that generates the message. + public: void Register(const std::string &_msgType, FactoryFn _factoryFn); + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: template + std::unique_ptr New(const std::string &_msgType) + { + return detail::dynamic_message_cast(New(_msgType)); + } + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \param[in] _args Message arguments. This will populate the message. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: template + std::unique_ptr New(const std::string &_msgType, + const std::string &_args) + { + return detail::dynamic_message_cast(New(_msgType, _args)); + } + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: MessagePtr New(const std::string &_msgType); + + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \param[in] _args Message arguments. This will populate the message. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: MessagePtr New( + const std::string &_msgType, const std::string &_args); + + /// \brief Get all the message types + /// \param[out] _types Vector of strings of the message types. + public: void Types(std::vector &_types); + + /// \brief Load a collection of descriptor .desc files. + /// \param[in] _paths A set of directories containing .desc decriptor + /// files. Each directory should be separated by ":". + public: void LoadDescriptors(const std::string &_paths); + + /// \brief A list of registered message types + private: FactoryFnCollection msgMap; + + /// \brief Pointer to dynamic factory implementation + GZ_UTILS_UNIQUE_IMPL_PTR_FWD(gz::msgs::DynamicFactory, dynamicFactory) + }; +} +} // namespace gz::msgs +#endif // GZ_MSGS_MESSAGE_FACTORY_HH_ diff --git a/include/gz/msgs/PointCloudPackedUtils.hh b/core/include/gz/msgs/PointCloudPackedUtils.hh similarity index 62% rename from include/gz/msgs/PointCloudPackedUtils.hh rename to core/include/gz/msgs/PointCloudPackedUtils.hh index d0fe27cf..f746f8c0 100644 --- a/include/gz/msgs/PointCloudPackedUtils.hh +++ b/core/include/gz/msgs/PointCloudPackedUtils.hh @@ -26,15 +26,97 @@ #include #include #include +#include #include #include "gz/msgs/config.hh" #include "gz/msgs/detail/PointCloudPackedUtils.hh" +#include namespace gz { namespace msgs { +///////////////////////////////////////////////// +inline void InitPointCloudPacked(msgs::PointCloudPacked &_msg, + const std::string &_frameId, bool _memoryAligned, + const std::vector> &_fields) +{ + uint32_t offset = 0; + + // Helper function that will set a single field. + std::function initPointCloudPackedHelper = + [&](const std::string &_name, + msgs::PointCloudPacked::Field::DataType _type) -> void + { + msgs::PointCloudPacked::Field *newField = _msg.add_field(); + newField->set_name(_name); + newField->set_count(1); + newField->set_datatype(_type); + newField->set_offset(offset); + switch (_type) + { + case msgs::PointCloudPacked::Field::INT8: + case msgs::PointCloudPacked::Field::UINT8: + offset += 1; + break; + case msgs::PointCloudPacked::Field::INT16: + case msgs::PointCloudPacked::Field::UINT16: + offset += 2; + break; + case msgs::PointCloudPacked::Field::INT32: + case msgs::PointCloudPacked::Field::UINT32: + case msgs::PointCloudPacked::Field::FLOAT32: + offset += 4; + break; + case msgs::PointCloudPacked::Field::FLOAT64: + offset += 8; + break; + // LCOV_EXCL_START + default: + std::cerr << "PointCloudPacked field datatype of [" + << _type << "] is invalid.\n"; + break; + // LCOV_EXCL_STOP + } + }; + + // Set the frame + _msg.mutable_header()->clear_data(); + msgs::Header::Map *frame = _msg.mutable_header()->add_data(); + frame->set_key("frame_id"); + frame->add_value(_frameId); + + _msg.clear_field(); + // Setup the point cloud message. + for (const std::pair &field : _fields) + { + if (field.first == "xyz") + { + initPointCloudPackedHelper("x", field.second); + initPointCloudPackedHelper("y", field.second); + initPointCloudPackedHelper("z", field.second); + } + else + { + initPointCloudPackedHelper(field.first, field.second); + } + + // Memory align the field. + if (_memoryAligned) + offset = math::roundUpMultiple(offset, sizeof(size_t)); + } + + // Set the point_step + if (_memoryAligned) + _msg.set_point_step(math::roundUpMultiple(offset, sizeof(size_t))); + else + _msg.set_point_step(offset); +} + /// \brief Class that can iterate over a PointCloudPacked message. /// /// E.g, you create your message and reserve space for data as follows: diff --git a/core/include/gz/msgs/Utility.hh b/core/include/gz/msgs/Utility.hh new file mode 100644 index 00000000..cd8963f9 --- /dev/null +++ b/core/include/gz/msgs/Utility.hh @@ -0,0 +1,38 @@ +/* + * Copyright (C) 2016 Open Source Robotics Foundation + * + * 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. + * +*/ +#ifndef GZ_MSGS_UTILITY_HH_ +#define GZ_MSGS_UTILITY_HH_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#endif // GZ_MSGS_UTILITY_HH_ diff --git a/include/gz/msgs/config.hh.in b/core/include/gz/msgs/config.hh.in similarity index 100% rename from include/gz/msgs/config.hh.in rename to core/include/gz/msgs/config.hh.in diff --git a/core/include/gz/msgs/convert/AxisAlignedBox.hh b/core/include/gz/msgs/convert/AxisAlignedBox.hh new file mode 100644 index 00000000..d49fbc8d --- /dev/null +++ b/core/include/gz/msgs/convert/AxisAlignedBox.hh @@ -0,0 +1,63 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_AXISALIGNEDBOX_HH_ +#define GZ_MSGS_CONVERT_AXISALIGNEDBOX_HH_ + +#include + +// Message Headers +#include "gz/msgs/axis_aligned_box.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::AxisAlignedBox *_msg, + const gz::math::AxisAlignedBox &_data) +{ + Set(_msg->mutable_min_corner(), _data.Min()); + Set(_msg->mutable_max_corner(), _data.Max()); +} + +inline void Set(gz::math::AxisAlignedBox *_data, + const gz::msgs::AxisAlignedBox &_msg) +{ + Set(&_data->Min(), _msg.min_corner()); + Set(&_data->Max(), _msg.max_corner()); +} + +inline gz::msgs::AxisAlignedBox Convert(const gz::math::AxisAlignedBox &_data) +{ + gz::msgs::AxisAlignedBox ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::AxisAlignedBox Convert(const gz::msgs::AxisAlignedBox &_msg) +{ + gz::math::AxisAlignedBox ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/Color.hh b/core/include/gz/msgs/convert/Color.hh new file mode 100644 index 00000000..1c832038 --- /dev/null +++ b/core/include/gz/msgs/convert/Color.hh @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_COLOR_HH_ +#define GZ_MSGS_CONVERT_COLOR_HH_ + +// Message Headers +#include "gz/msgs/color.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::Color *_msg, const gz::math::Color &_data) +{ + _msg->set_r(_data.R()); + _msg->set_g(_data.G()); + _msg->set_b(_data.B()); + _msg->set_a(_data.A()); +} + +inline void Set(gz::math::Color *_data, const gz::msgs::Color &_msg) +{ + _data->Set(_msg.r(), _msg.g(), _msg.b(), _msg.a()); +} + +inline gz::msgs::Color Convert(const gz::math::Color &_data) +{ + gz::msgs::Color ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::Color Convert(const gz::msgs::Color &_msg) +{ + gz::math::Color ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/DiscoveryType.hh b/core/include/gz/msgs/convert/DiscoveryType.hh new file mode 100644 index 00000000..d9b78fae --- /dev/null +++ b/core/include/gz/msgs/convert/DiscoveryType.hh @@ -0,0 +1,122 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_DISCOVERYTYPE_HH_ +#define GZ_MSGS_CONVERT_DISCOVERYTYPE_HH_ + +// Message Headers +#include "gz/msgs/discovery.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////////////////// +inline msgs::Discovery::Type ConvertDiscoveryType(const std::string &_str) +{ + msgs::Discovery::Type result = msgs::Discovery::UNINITIALIZED; + + if (_str == "UNINITIALIZED") + { + result = msgs::Discovery::UNINITIALIZED; + } + else if (_str == "ADVERTISE") + { + result = msgs::Discovery::ADVERTISE; + } + else if (_str == "SUBSCRIBE") + { + result = msgs::Discovery::SUBSCRIBE; + } + else if (_str == "UNADVERTISE") + { + result = msgs::Discovery::UNADVERTISE; + } + else if (_str == "HEARTBEAT") + { + result = msgs::Discovery::HEARTBEAT; + } + else if (_str == "BYE") + { + result = msgs::Discovery::BYE; + } + else if (_str == "NEW_CONNECTION") + { + result = msgs::Discovery::NEW_CONNECTION; + } + else if (_str == "END_CONNECTION") + { + result = msgs::Discovery::END_CONNECTION; + } + else if (_str == "SUBSCRIBERS_REQ") + { + result = msgs::Discovery::SUBSCRIBERS_REQ; + } + else if (_str == "SUBSCRIBERS_REP") + { + result = msgs::Discovery::SUBSCRIBERS_REP; + } + else + { + std::cerr << "Unrecognized DiscoveryType[" + << _str + << "], returning msgs::Discovery::UNINITIALIZED" + << std::endl; + } + return result; +} + +///////////////////////////////////////////// +inline std::string ConvertDiscoveryType(const msgs::Discovery::Type &_type) +{ + switch (_type) + { + default: + case msgs::Discovery::UNINITIALIZED: + return "UNINITIALIZED"; + case msgs::Discovery::ADVERTISE: + return "ADVERTISE"; + case msgs::Discovery::SUBSCRIBE: + return "SUBSCRIBE"; + case msgs::Discovery::UNADVERTISE: + return "UNADVERTISE"; + case msgs::Discovery::HEARTBEAT: + return "HEARTBEAT"; + case msgs::Discovery::BYE: + return "BYE"; + case msgs::Discovery::NEW_CONNECTION: + return "NEW_CONNECTION"; + case msgs::Discovery::END_CONNECTION: + return "END_CONNECTION"; + case msgs::Discovery::SUBSCRIBERS_REQ: + return "SUBSCRIBERS_REQ"; + case msgs::Discovery::SUBSCRIBERS_REP: + return "SUBSCRIBERS_REP"; + }; +} + +// This is for API compatibility +inline std::string ToString(const msgs::Discovery::Type &_t) +{ + return ConvertDiscoveryType(_t); +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_DISCOVERYTYPE_HH_ diff --git a/core/include/gz/msgs/convert/FuelMetadata.hh b/core/include/gz/msgs/convert/FuelMetadata.hh new file mode 100644 index 00000000..e58d58ab --- /dev/null +++ b/core/include/gz/msgs/convert/FuelMetadata.hh @@ -0,0 +1,258 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_FUELMETADATA_HH_ +#define GZ_MSGS_CONVERT_FUELMETADATA_HH_ + +// Message Headers +#include "gz/msgs/fuel_metadata.pb.h" + +// Data Headers +#include +#include +#include + +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////////////////////// +inline bool ConvertFuelMetadata(const std::string &_modelConfigStr, + msgs::FuelMetadata &_meta) +{ + gz::msgs::FuelMetadata meta; + + auto trimmed = [](std::string _s) -> std::string { + // Left trim + _s.erase(_s.begin(), std::find_if(_s.begin(), _s.end(), + [](int c) {return !std::isspace(c);})); + + // Right trim + _s.erase(std::find_if(_s.rbegin(), _s.rend(), + [](int c) {return !std::isspace(c);}).base(), _s.end()); + + return _s; + }; + + // Load the model config into tinyxml + tinyxml2::XMLDocument modelConfigDoc; + if (modelConfigDoc.Parse(_modelConfigStr.c_str()) != + tinyxml2::XML_SUCCESS) + { + std::cerr << "Unable to parse model config XML string.\n"; + return false; + } + + // Get the top level or element. + tinyxml2::XMLElement *topElement = modelConfigDoc.FirstChildElement( + "model"); + bool isModel = true; + if (!topElement) + { + topElement = modelConfigDoc.FirstChildElement("world"); + if (!topElement) + { + std::cerr << "Model config string does not contain a " + << " or element\n"; + return false; + } + isModel = false; + } + + // Read the name, which is a mandatory element. + tinyxml2::XMLElement *elem = topElement->FirstChildElement("name"); + if (!elem || !elem->GetText()) + { + std::cerr << "Model config string does not contain a element\n"; + return false; + } + meta.set_name(trimmed(elem->GetText())); + + // Read the version, if present. + elem = topElement->FirstChildElement("version"); + if (elem && elem->GetText()) + { + auto version = std::stoi(trimmed(elem->GetText())); + meta.set_version(version); + } + + // Read the description, if present. + elem = topElement->FirstChildElement("description"); + if (elem && elem->GetText()) + meta.set_description(trimmed(elem->GetText())); + + // Read the dependencies, if any. + elem = topElement->FirstChildElement("depend"); + while (elem) + { + auto modelElem = elem->FirstChildElement("model"); + if (modelElem) + { + auto uriElem = modelElem->FirstChildElement("uri"); + if (uriElem) + { + auto dependency = meta.add_dependencies(); + dependency->set_uri(uriElem->GetText()); + } + } + elem = elem->NextSiblingElement("depend"); + } + + // Read the authors, if any. + elem = topElement->FirstChildElement("author"); + while (elem) + { + gz::msgs::FuelMetadata::Contact *author = meta.add_authors(); + // Get the author name and email + if (elem->FirstChildElement("name") && + elem->FirstChildElement("name")->GetText()) + { + author->set_name(trimmed(elem->FirstChildElement("name")->GetText())); + } + if (elem->FirstChildElement("email") && + elem->FirstChildElement("email")->GetText()) + { + author->set_email( + trimmed(elem->FirstChildElement("email")->GetText())); + } + + elem = elem->NextSiblingElement("author"); + } + + // Get the most recent SDF file + elem = topElement->FirstChildElement("sdf"); + math::SemanticVersion maxVer; + while (elem) + { + if (elem->GetText() && elem->Attribute("version")) + { + std::string verStr = elem->Attribute("version"); + math::SemanticVersion ver(trimmed(verStr)); + if (ver > maxVer) + { + gz::msgs::Version *verMsg; + + if (isModel) + { + meta.mutable_model()->mutable_file_format()->set_name("sdf"); + verMsg = + meta.mutable_model()->mutable_file_format()->mutable_version(); + meta.mutable_model()->set_file(trimmed(elem->GetText())); + } + else + { + meta.mutable_world()->mutable_file_format()->set_name("sdf"); + verMsg = + meta.mutable_world()->mutable_file_format()->mutable_version(); + meta.mutable_world()->set_file(trimmed(elem->GetText())); + } + + verMsg->set_major(ver.Major()); + verMsg->set_minor(ver.Minor()); + verMsg->set_patch(ver.Patch()); + verMsg->set_prerelease(ver.Prerelease()); + verMsg->set_build(ver.Build()); + } + } + + elem = elem->NextSiblingElement("sdf"); + } + if (meta.model().file().empty() && meta.world().file().empty()) + { + std::cerr << "Model config string does not contain an element\n"; + return false; + } + + _meta.CopyFrom(meta); + return true; +} + +///////////////////////////////////////////////// +inline bool ConvertFuelMetadata(const msgs::FuelMetadata &_meta, + std::string &_modelConfigStr) +{ + std::ostringstream out; + + // Output opening tag. + if (_meta.has_model()) + { + if (_meta.model().file_format().name() != "sdf") + { + std::cerr << "Model _metadata does not contain an SDF file.\n"; + return false; + } + + out << "\n" + << " \n" + << " " + << _meta.model().file() << "\n"; + } + else + { + if (_meta.world().file_format().name() != "sdf") + { + std::cerr << "World _metadata does not contain an SDF file.\n"; + return false; + } + + out << "\n" + << " \n" + << " " + << _meta.world().file() << "\n"; + } + + out << " " << _meta.name() << "\n" + << " " << _meta.version() << "\n" + << " " << _meta.description() << "\n"; + + // Output author information. + for (int i = 0; i < _meta.authors_size(); ++i) + { + out << " \n" + << " " << _meta.authors(i).name() << "\n" + << " " << _meta.authors(i).email() << "\n" + << " \n"; + } + + // Output dependency information. + for (int i = 0; i < _meta.dependencies_size(); ++i) + { + out << " \n" + << " \n" + << " " << _meta.dependencies(i).uri() << "\n" + << " \n" + << " \n"; + } + + // Output closing tag. + if (_meta.has_model()) + out << " \n"; + else + out << " \n"; + + _modelConfigStr = out.str(); + return true; +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_FUELMETADATA_HH_ diff --git a/core/include/gz/msgs/convert/GeometryType.hh b/core/include/gz/msgs/convert/GeometryType.hh new file mode 100644 index 00000000..e8152fd7 --- /dev/null +++ b/core/include/gz/msgs/convert/GeometryType.hh @@ -0,0 +1,156 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_GEOMETRYTYPE_HH_ +#define GZ_MSGS_CONVERT_GEOMETRYTYPE_HH_ + +// Message Headers +#include "gz/msgs/geometry.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////////////////////// +inline msgs::Geometry::Type ConvertGeometryType(const std::string &_str) +{ + msgs::Geometry::Type result = msgs::Geometry::BOX; + if (_str == "box") + { + result = msgs::Geometry::BOX; + } + else if (_str == "capsule") + { + result = msgs::Geometry::CAPSULE; + } + else if (_str == "cylinder") + { + result = msgs::Geometry::CYLINDER; + } + else if (_str == "ellipsoid") + { + result = msgs::Geometry::ELLIPSOID; + } + else if (_str == "sphere") + { + result = msgs::Geometry::SPHERE; + } + else if (_str == "plane") + { + result = msgs::Geometry::PLANE; + } + else if (_str == "image") + { + result = msgs::Geometry::IMAGE; + } + else if (_str == "heightmap") + { + result = msgs::Geometry::HEIGHTMAP; + } + else if (_str == "mesh") + { + result = msgs::Geometry::MESH; + } + else if (_str == "polyline") + { + result = msgs::Geometry::POLYLINE; + } + else + { + std::cerr << "Unrecognized Geometry::Type [" + << _str + << "], returning msgs::Geometry::BOX" + << std::endl; + } + + return result; +} + +///////////////////////////////////////////////// +inline std::string ConvertGeometryType(const msgs::Geometry::Type _type) +{ + std::string result; + switch (_type) + { + case msgs::Geometry::BOX: + { + result = "box"; + break; + } + case msgs::Geometry::CAPSULE: + { + result = "capsule"; + break; + } + case msgs::Geometry::CYLINDER: + { + result = "cylinder"; + break; + } + case msgs::Geometry::ELLIPSOID: + { + result = "ellipsoid"; + break; + } + case msgs::Geometry::SPHERE: + { + result = "sphere"; + break; + } + case msgs::Geometry::PLANE: + { + result = "plane"; + break; + } + case msgs::Geometry::IMAGE: + { + result = "image"; + break; + } + case msgs::Geometry::HEIGHTMAP: + { + result = "heightmap"; + break; + } + case msgs::Geometry::MESH: + { + result = "mesh"; + break; + } + case msgs::Geometry::POLYLINE: + { + result = "polyline"; + break; + } + default: + { + result = "unknown"; + std::cerr << "Unrecognized Geometry::Type [" + << _type + << "], returning 'unknown'" + << std::endl; + break; + } + } + return result; +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_GEOMETRYTYPE_HH_ diff --git a/core/include/gz/msgs/convert/Inertial.hh b/core/include/gz/msgs/convert/Inertial.hh new file mode 100644 index 00000000..7e46b507 --- /dev/null +++ b/core/include/gz/msgs/convert/Inertial.hh @@ -0,0 +1,171 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_INERTIAL_HH_ +#define GZ_MSGS_CONVERT_INERTIAL_HH_ + +#include +#include + +// Message Headers +#include "gz/msgs/inertial.pb.h" + +// Data Headers +#include +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::Inertial *_msg, const gz::math::MassMatrix3d &_data) +{ + _msg->set_mass(_data.Mass()); + _msg->set_ixx(_data.Ixx()); + _msg->set_iyy(_data.Iyy()); + _msg->set_izz(_data.Izz()); + _msg->set_ixy(_data.Ixy()); + _msg->set_ixz(_data.Ixz()); + _msg->set_iyz(_data.Iyz()); + _msg->mutable_pose()->mutable_orientation()->set_w(1); +} + +inline void Set(gz::math::MassMatrix3d *_data, const gz::msgs::Inertial &_msg) +{ + _data->SetMass(_msg.mass()); + _data->SetIxx(_msg.ixx()); + _data->SetIyy(_msg.iyy()); + _data->SetIzz(_msg.izz()); + _data->SetIxy(_msg.ixy()); + _data->SetIxz(_msg.ixz()); + _data->SetIyz(_msg.iyz()); +} + +inline gz::msgs::Inertial Convert(const gz::math::MassMatrix3d &_data) +{ + gz::msgs::Inertial ret; + Set(&ret, _data); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::Inertial *_msg, const gz::math::Inertiald &_data) +{ + Set(_msg, _data.MassMatrix()); + Set(_msg->mutable_pose(), _data.Pose()); + + if (_data.FluidAddedMass().has_value()) + { + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(0, 0)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(0, 1)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(0, 2)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(0, 3)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(0, 4)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(0, 5)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(1, 1)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(1, 2)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(1, 3)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(1, 4)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(1, 5)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(2, 2)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(2, 3)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(2, 4)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(2, 5)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(3, 3)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(3, 4)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(3, 5)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(4, 4)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(4, 5)); + _msg->add_fluid_added_mass(_data.FluidAddedMass().value()(5, 5)); + } +} + +inline void Set(gz::math::Inertiald *_data, const gz::msgs::Inertial &_msg) +{ + gz::math::MassMatrix3d to_set = _data->MassMatrix(); + Set(&to_set, _msg); + _data->SetMassMatrix(to_set); + + gz::math::Pose3d pose_to_set = _data->Pose(); + Set(&pose_to_set, _msg.pose()); + _data->SetPose(pose_to_set); + + if (_msg.fluid_added_mass_size() == 21) + { + math::Matrix6d addedMass{ + _msg.fluid_added_mass(0), + _msg.fluid_added_mass(1), + _msg.fluid_added_mass(2), + _msg.fluid_added_mass(3), + _msg.fluid_added_mass(4), + _msg.fluid_added_mass(5), + + _msg.fluid_added_mass(1), + _msg.fluid_added_mass(6), + _msg.fluid_added_mass(7), + _msg.fluid_added_mass(8), + _msg.fluid_added_mass(9), + _msg.fluid_added_mass(10), + + _msg.fluid_added_mass(2), + _msg.fluid_added_mass(7), + _msg.fluid_added_mass(11), + _msg.fluid_added_mass(12), + _msg.fluid_added_mass(13), + _msg.fluid_added_mass(14), + + _msg.fluid_added_mass(3), + _msg.fluid_added_mass(8), + _msg.fluid_added_mass(12), + _msg.fluid_added_mass(15), + _msg.fluid_added_mass(16), + _msg.fluid_added_mass(17), + + _msg.fluid_added_mass(4), + _msg.fluid_added_mass(9), + _msg.fluid_added_mass(13), + _msg.fluid_added_mass(16), + _msg.fluid_added_mass(18), + _msg.fluid_added_mass(19), + + _msg.fluid_added_mass(5), + _msg.fluid_added_mass(10), + _msg.fluid_added_mass(14), + _msg.fluid_added_mass(17), + _msg.fluid_added_mass(19), + _msg.fluid_added_mass(20) + }; + _data->SetFluidAddedMass(addedMass); + } +} + +inline gz::msgs::Inertial Convert(const gz::math::Inertiald &_data) +{ + gz::msgs::Inertial ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::Inertiald Convert(const gz::msgs::Inertial &_msg) +{ + gz::math::Inertiald ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/JointType.hh b/core/include/gz/msgs/convert/JointType.hh new file mode 100644 index 00000000..9803b668 --- /dev/null +++ b/core/include/gz/msgs/convert/JointType.hh @@ -0,0 +1,147 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_JOINTTYPE_HH_ +#define GZ_MSGS_CONVERT_JOINTTYPE_HH_ + +// Message Headers +#include "gz/msgs/joint.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////////////////// +inline msgs::Joint::Type ConvertJointType(const std::string &_str) +{ + msgs::Joint::Type result = msgs::Joint::REVOLUTE; + if (_str == "revolute") + { + result = msgs::Joint::REVOLUTE; + } + else if (_str == "revolute2") + { + result = msgs::Joint::REVOLUTE2; + } + else if (_str == "prismatic") + { + result = msgs::Joint::PRISMATIC; + } + else if (_str == "universal") + { + result = msgs::Joint::UNIVERSAL; + } + else if (_str == "ball") + { + result = msgs::Joint::BALL; + } + else if (_str == "screw") + { + result = msgs::Joint::SCREW; + } + else if (_str == "gearbox") + { + result = msgs::Joint::GEARBOX; + } + else if (_str == "fixed") + { + result = msgs::Joint::FIXED; + } + else if (_str == "continuous") + { + result = msgs::Joint::CONTINUOUS; + } + else + { + std::cerr << "Unrecognized JointType [" + << _str + << "], returning msgs::Joint::REVOLUTE" + << std::endl; + } + return result; +} + +///////////////////////////////////////////// +inline std::string ConvertJointType(const msgs::Joint::Type &_type) +{ + std::string result; + switch (_type) + { + case msgs::Joint::REVOLUTE: + { + result = "revolute"; + break; + } + case msgs::Joint::REVOLUTE2: + { + result = "revolute2"; + break; + } + case msgs::Joint::PRISMATIC: + { + result = "prismatic"; + break; + } + case msgs::Joint::UNIVERSAL: + { + result = "universal"; + break; + } + case msgs::Joint::BALL: + { + result = "ball"; + break; + } + case msgs::Joint::SCREW: + { + result = "screw"; + break; + } + case msgs::Joint::GEARBOX: + { + result = "gearbox"; + break; + } + case msgs::Joint::FIXED: + { + result = "fixed"; + break; + } + case msgs::Joint::CONTINUOUS: + { + result = "continuous"; + break; + } + default: + { + result = "unknown"; + std::cerr << "Unrecognized JointType [" + << _type + << "], returning 'unknown'" + << std::endl; + break; + } + } + return result; +} + +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_JOINTTYPE_HH_ diff --git a/core/include/gz/msgs/convert/PixelFormatType.hh b/core/include/gz/msgs/convert/PixelFormatType.hh new file mode 100644 index 00000000..c195b0d6 --- /dev/null +++ b/core/include/gz/msgs/convert/PixelFormatType.hh @@ -0,0 +1,160 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_PIXELFORMATTYPE_HH_ +#define GZ_MSGS_CONVERT_PIXELFORMATTYPE_HH_ + +// Message Headers +#include "gz/msgs/image.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////////////////// +inline msgs::PixelFormatType ConvertPixelFormatType(const std::string &_str) +{ + if (_str == "L_INT8") + { + return msgs::PixelFormatType::L_INT8; + } + else if (_str == "L_INT16") + { + return msgs::PixelFormatType::L_INT16; + } + else if (_str == "RGB_INT8") + { + return msgs::PixelFormatType::RGB_INT8; + } + else if (_str == "RGBA_INT8") + { + return msgs::PixelFormatType::RGBA_INT8; + } + else if (_str == "BGRA_INT8") + { + return msgs::PixelFormatType::BGRA_INT8; + } + else if (_str == "RGB_INT16") + { + return msgs::PixelFormatType::RGB_INT16; + } + else if (_str == "RGB_INT32") + { + return msgs::PixelFormatType::RGB_INT32; + } + else if (_str == "BGR_INT8") + { + return msgs::PixelFormatType::BGR_INT8; + } + else if (_str == "BGR_INT16") + { + return msgs::PixelFormatType::BGR_INT16; + } + else if (_str == "BGR_INT32") + { + return msgs::PixelFormatType::BGR_INT32; + } + else if (_str == "R_FLOAT16") + { + return msgs::PixelFormatType::R_FLOAT16; + } + else if (_str == "RGB_FLOAT16") + { + return msgs::PixelFormatType::RGB_FLOAT16; + } + else if (_str == "R_FLOAT32") + { + return msgs::PixelFormatType::R_FLOAT32; + } + else if (_str == "RGB_FLOAT32") + { + return msgs::PixelFormatType::RGB_FLOAT32; + } + else if (_str == "BAYER_RGGB8") + { + return msgs::PixelFormatType::BAYER_RGGB8; + } + else if (_str == "BAYER_BGGR8") + { + return msgs::PixelFormatType::BAYER_BGGR8; + } + else if (_str == "BAYER_GBRG8") + { + return msgs::PixelFormatType::BAYER_GBRG8; + } + else if (_str == "BAYER_GRBG8") + { + return msgs::PixelFormatType::BAYER_GRBG8; + } + + return msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT; +} + +///////////////////////////////////////////// +inline std::string ConvertPixelFormatType(const msgs::PixelFormatType &_t) +{ + switch (_t) + { + default: + case msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT: + return "UNKNOWN_PIXEL_FORMAT"; + case msgs::PixelFormatType::L_INT8: + return "L_INT8"; + case msgs::PixelFormatType::L_INT16: + return "L_INT16"; + case msgs::PixelFormatType::RGB_INT8: + return "RGB_INT8"; + case msgs::PixelFormatType::RGBA_INT8: + return "RGBA_INT8"; + case msgs::PixelFormatType::BGRA_INT8: + return "BGRA_INT8"; + case msgs::PixelFormatType::RGB_INT16: + return "RGB_INT16"; + case msgs::PixelFormatType::RGB_INT32: + return "RGB_INT32"; + case msgs::PixelFormatType::BGR_INT8: + return "BGR_INT8"; + case msgs::PixelFormatType::BGR_INT16: + return "BGR_INT16"; + case msgs::PixelFormatType::BGR_INT32: + return "BGR_INT32"; + case msgs::PixelFormatType::R_FLOAT16: + return "R_FLOAT16"; + case msgs::PixelFormatType::RGB_FLOAT16: + return "RGB_FLOAT16"; + case msgs::PixelFormatType::R_FLOAT32: + return "R_FLOAT32"; + case msgs::PixelFormatType::RGB_FLOAT32: + return "RGB_FLOAT32"; + case msgs::PixelFormatType::BAYER_RGGB8: + return "BAYER_RGGB8"; + case msgs::PixelFormatType::BAYER_BGGR8: + return "BAYER_BGGR8"; + case msgs::PixelFormatType::BAYER_GBRG8: + return "BAYER_GBRG8"; + case msgs::PixelFormatType::BAYER_GRBG8: + return "BAYER_GRBG8"; + }; +} + + +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_PIXELFORMATTYPE_HH_ diff --git a/core/include/gz/msgs/convert/Plane.hh b/core/include/gz/msgs/convert/Plane.hh new file mode 100644 index 00000000..b10e19ae --- /dev/null +++ b/core/include/gz/msgs/convert/Plane.hh @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_PLANE_HH_ +#define GZ_MSGS_CONVERT_PLANE_HH_ + +#include +#include + +// Message Headers +#include "gz/msgs/planegeom.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::PlaneGeom *_msg, const gz::math::Planed &_data) +{ + Set(_msg->mutable_normal(), _data.Normal()); + _msg->mutable_size()->set_x(_data.Size().X()); + _msg->mutable_size()->set_y(_data.Size().Y()); + _msg->set_d(_data.Offset()); +} + +inline void Set(gz::math::Planed *_data, const gz::msgs::PlaneGeom &_msg) +{ + _data->Set( + Convert(_msg.normal()), + Convert(_msg.size()), + _msg.d() + ); +} + +inline gz::msgs::PlaneGeom Convert(const gz::math::Planed &_data) +{ + gz::msgs::PlaneGeom ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::Planed Convert(const gz::msgs::PlaneGeom &_msg) +{ + gz::math::Planed ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/Pose.hh b/core/include/gz/msgs/convert/Pose.hh new file mode 100644 index 00000000..b9ff158c --- /dev/null +++ b/core/include/gz/msgs/convert/Pose.hh @@ -0,0 +1,64 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_POSE_HH_ +#define GZ_MSGS_CONVERT_POSE_HH_ + +#include +#include + +// Message Headers +#include "gz/msgs/details/quaternion.pb.h" +#include "gz/msgs/pose.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::Pose *_msg, const gz::math::Pose3d &_data) +{ + Set(_msg->mutable_position(), _data.Pos()); + Set(_msg->mutable_orientation(), _data.Rot()); +} + +inline void Set(gz::math::Pose3d *_data, const gz::msgs::Pose &_msg) +{ + auto pos = Convert(_msg.position()); + auto orientation = Convert(_msg.orientation()); + _data->Set(pos, orientation); +} + +inline gz::msgs::Pose Convert(const gz::math::Pose3d &_data) +{ + gz::msgs::Pose ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::Pose3d Convert(const gz::msgs::Pose &_msg) +{ + gz::math::Pose3d ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/Quaternion.hh b/core/include/gz/msgs/convert/Quaternion.hh new file mode 100644 index 00000000..2f243d71 --- /dev/null +++ b/core/include/gz/msgs/convert/Quaternion.hh @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_QUATERNION_HH_ +#define GZ_MSGS_CONVERT_QUATERNION_HH_ + +// Message Headers +#include "gz/msgs/quaternion.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::Quaternion *_msg, const gz::math::Quaterniond &_data) +{ + _msg->set_w(_data.W()); + _msg->set_x(_data.X()); + _msg->set_y(_data.Y()); + _msg->set_z(_data.Z()); +} + +inline void Set(gz::math::Quaterniond *_data, const gz::msgs::Quaternion &_msg) +{ + _data->Set(_msg.w(), _msg.x(), _msg.y(), _msg.z()); +} + +inline gz::msgs::Quaternion Convert(const gz::math::Quaterniond &_data) +{ + gz::msgs::Quaternion ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::Quaterniond Convert(const gz::msgs::Quaternion &_msg) +{ + gz::math::Quaterniond ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/ShaderType.hh b/core/include/gz/msgs/convert/ShaderType.hh new file mode 100644 index 00000000..7a7aef66 --- /dev/null +++ b/core/include/gz/msgs/convert/ShaderType.hh @@ -0,0 +1,102 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_SHADERTYPE_HH_ +#define GZ_MSGS_CONVERT_SHADERTYPE_HH_ + +// Message Headers +#include "gz/msgs/material.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////////////////////// +inline msgs::Material::ShaderType ConvertShaderType(const std::string &_str) +{ + auto result = msgs::Material::VERTEX; + if (_str == "vertex") + { + result = msgs::Material::VERTEX; + } + else if (_str == "pixel") + { + result = msgs::Material::PIXEL; + } + else if (_str == "normal_map_object_space") + { + result = msgs::Material::NORMAL_MAP_OBJECT_SPACE; + } + else if (_str == "normal_map_tangent_space") + { + result = msgs::Material::NORMAL_MAP_TANGENT_SPACE; + } + else + { + std::cerr << "Unrecognized Material::ShaderType [" + << _str + << "], returning msgs::Material::VERTEX" + << std::endl; + } + return result; +} + +///////////////////////////////////////////////// +inline std::string ConvertShaderType(const msgs::Material::ShaderType &_type) +{ + std::string result; + switch (_type) + { + case msgs::Material::VERTEX: + { + result = "vertex"; + break; + } + case msgs::Material::PIXEL: + { + result = "pixel"; + break; + } + case msgs::Material::NORMAL_MAP_OBJECT_SPACE: + { + result = "normal_map_object_space"; + break; + } + case msgs::Material::NORMAL_MAP_TANGENT_SPACE: + { + result = "normal_map_tangent_space"; + break; + } + default: + { + result = "unknown"; + std::cerr << "Unrecognized Material::ShaderType [" + << _type + << "], returning 'unknown'" + << std::endl; + break; + } + } + return result; +} + +} // namespce +} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_SHADERTYPE_HH_ diff --git a/core/include/gz/msgs/convert/SphericalCoordinates.hh b/core/include/gz/msgs/convert/SphericalCoordinates.hh new file mode 100644 index 00000000..cb08faa1 --- /dev/null +++ b/core/include/gz/msgs/convert/SphericalCoordinates.hh @@ -0,0 +1,118 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_SPHERICALCOORDINATES_HH_ +#define GZ_MSGS_CONVERT_SPHERICALCOORDINATES_HH_ + +// Message Headers +#include "gz/msgs/spherical_coordinates.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::SphericalCoordinates *_msg, + const gz::math::SphericalCoordinates &_data) +{ + if (_data.Surface() == math::SphericalCoordinates::EARTH_WGS84) + { + _msg->set_surface_model(msgs::SphericalCoordinates::EARTH_WGS84); + } + else if (_data.Surface() == math::SphericalCoordinates::MOON_SCS) + { + _msg->set_surface_model(msgs::SphericalCoordinates::MOON_SCS); + } + else if (_data.Surface() == + math::SphericalCoordinates::CUSTOM_SURFACE) + { + _msg->set_surface_model( + msgs::SphericalCoordinates::CUSTOM_SURFACE); + _msg->set_surface_axis_equatorial(_data.SurfaceAxisEquatorial()); + _msg->set_surface_axis_polar(_data.SurfaceAxisPolar()); + } + else + { + std::cerr << "Unrecognized spherical surface type [" + << _data.Surface() + << "]. Not populating message field." << std::endl; + } + _msg->set_latitude_deg(_data.LatitudeReference().Degree()); + _msg->set_longitude_deg(_data.LongitudeReference().Degree()); + _msg->set_elevation(_data.ElevationReference()); + _msg->set_heading_deg(_data.HeadingOffset().Degree()); +} + +inline void Set(gz::math::SphericalCoordinates *_data, + const gz::msgs::SphericalCoordinates &_msg) +{ + if (_msg.surface_model() == msgs::SphericalCoordinates::EARTH_WGS84) + { + _data->SetSurface(math::SphericalCoordinates::EARTH_WGS84); + } + else if (_msg.surface_model() == msgs::SphericalCoordinates::MOON_SCS) + { + _data->SetSurface(math::SphericalCoordinates::MOON_SCS); + } + else if (_msg.surface_model() == msgs::SphericalCoordinates::CUSTOM_SURFACE) + { + _data->SetSurface(math::SphericalCoordinates::CUSTOM_SURFACE, + _msg.surface_axis_equatorial(), + _msg.surface_axis_polar()); + } + else + { + std::cerr << "Unrecognized spherical surface type [" + << _msg.surface_model() + << "]. Not populating data field." << std::endl; + } + + auto lat = gz::math::Angle(); + lat.SetDegree(_msg.latitude_deg()); + _data->SetLatitudeReference(lat); + + auto lon = gz::math::Angle(); + lon.SetDegree(_msg.longitude_deg()); + _data->SetLongitudeReference(lon); + + auto head = gz::math::Angle(); + head.SetDegree(_msg.heading_deg()); + _data->SetHeadingOffset(head); + + _data->SetElevationReference(_msg.elevation()); +} + +inline gz::msgs::SphericalCoordinates +Convert(const gz::math::SphericalCoordinates &_data) +{ + gz::msgs::SphericalCoordinates ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::SphericalCoordinates + Convert(const gz::msgs::SphericalCoordinates &_msg) +{ + gz::math::SphericalCoordinates ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/StdTypes.hh b/core/include/gz/msgs/convert/StdTypes.hh new file mode 100644 index 00000000..20e2bff8 --- /dev/null +++ b/core/include/gz/msgs/convert/StdTypes.hh @@ -0,0 +1,282 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_STDTYPES_HH_ +#define GZ_MSGS_CONVERT_STDTYPES_HH_ + +#include + +// Message Headers +#include "gz/msgs/boolean.pb.h" +#include "gz/msgs/double.pb.h" +#include "gz/msgs/float.pb.h" +#include "gz/msgs/int32.pb.h" +#include "gz/msgs/int64.pb.h" +#include "gz/msgs/stringmsg.pb.h" +#include "gz/msgs/time.pb.h" +#include "gz/msgs/uint32.pb.h" +#include "gz/msgs/uint64.pb.h" + +// Data Headers +#include +#include +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::Time *_msg, + const std::chrono::steady_clock::duration &_data) +{ + std::pair timeSecAndNsecs = + gz::math::durationToSecNsec(_data); + msgs::Time msg; + _msg->set_sec(timeSecAndNsecs.first); + _msg->set_nsec(timeSecAndNsecs.second); +} + +inline void Set(std::chrono::steady_clock::duration *_data, + const gz::msgs::Time &_msg) +{ + *_data = ( + std::chrono::seconds(_msg.sec()) + + std::chrono::nanoseconds(_msg.nsec())); +} + +inline gz::msgs::Time Convert(const std::chrono::steady_clock::duration &_data) +{ + gz::msgs::Time ret; + Set(&ret, _data); + return ret; +} + +inline std::chrono::steady_clock::duration +Convert(const gz::msgs::Time &_msg) +{ + std::chrono::steady_clock::duration ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::StringMsg *_msg, const std::string &_data) +{ + _msg->set_data(_data); +} + +inline void Set(gz::msgs::StringMsg *_msg, const char *_data) +{ + _msg->set_data(_data); +} + +inline void Set(std::string *_data, const gz::msgs::StringMsg &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::StringMsg Convert(const std::string &_data) +{ + gz::msgs::StringMsg ret; + Set(&ret, _data); + return ret; +} + +inline std::string Convert(const gz::msgs::StringMsg &_msg) +{ + std::string ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::Boolean *_msg, const bool &_data) +{ + _msg->set_data(_data); +} + +inline void Set(bool *_data, const gz::msgs::Boolean &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::Boolean Convert(const bool &_data) +{ + gz::msgs::Boolean ret; + Set(&ret, _data); + return ret; +} + +inline bool Convert(const gz::msgs::Boolean &_msg) +{ + bool ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::Int32 *_msg, const int32_t &_data) +{ + _msg->set_data(_data); +} + +inline void Set(int32_t *_data, const gz::msgs::Int32 &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::Int32 Convert(const int32_t &_data) +{ + gz::msgs::Int32 ret; + Set(&ret, _data); + return ret; +} + +inline int32_t Convert(const gz::msgs::Int32 &_msg) +{ + int32_t ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::UInt32 *_msg, const uint32_t &_data) +{ + _msg->set_data(_data); +} + +inline void Set(uint32_t *_data, const gz::msgs::UInt32 &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::UInt32 Convert(const uint32_t &_data) +{ + gz::msgs::UInt32 ret; + Set(&ret, _data); + return ret; +} + +inline uint32_t Convert(const gz::msgs::UInt32 &_msg) +{ + uint32_t ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::Int64 *_msg, const int64_t &_data) +{ + _msg->set_data(_data); +} + +inline void Set(int64_t *_data, const gz::msgs::Int64 &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::Int64 Convert(const int64_t &_data) +{ + gz::msgs::Int64 ret; + Set(&ret, _data); + return ret; +} + +inline int64_t Convert(const gz::msgs::Int64 &_msg) +{ + int64_t ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::UInt64 *_msg, const uint64_t &_data) +{ + _msg->set_data(_data); +} + +inline void Set(uint64_t *_data, const gz::msgs::UInt64 &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::UInt64 Convert(const uint64_t &_data) +{ + gz::msgs::UInt64 ret; + Set(&ret, _data); + return ret; +} + +inline uint64_t Convert(const gz::msgs::UInt64 &_msg) +{ + uint64_t ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::Float *_msg, const float &_data) +{ + _msg->set_data(_data); +} + +inline void Set(float *_data, const gz::msgs::Float &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::Float Convert(const float &_data) +{ + gz::msgs::Float ret; + Set(&ret, _data); + return ret; +} + +inline float Convert(const gz::msgs::Float &_msg) +{ + float ret; + Set(&ret, _msg); + return ret; +} + +///////////////////////////////// +inline void Set(gz::msgs::Double *_msg, const double &_data) +{ + _msg->set_data(_data); +} + +inline void Set(double *_data, const gz::msgs::Double &_msg) +{ + *_data = _msg.data(); +} + +inline gz::msgs::Double Convert(const double &_data) +{ + gz::msgs::Double ret; + Set(&ret, _data); + return ret; +} + +inline double Convert(const gz::msgs::Double &_msg) +{ + double ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/Vector2.hh b/core/include/gz/msgs/convert/Vector2.hh new file mode 100644 index 00000000..6a467b2b --- /dev/null +++ b/core/include/gz/msgs/convert/Vector2.hh @@ -0,0 +1,57 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_VECTOR2_HH_ +#define GZ_MSGS_CONVERT_VECTOR2_HH_ + +// Message Headers +#include "gz/msgs/vector2d.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::Vector2d *_msg, const gz::math::Vector2d &_data) +{ + _msg->set_x(_data.X()); + _msg->set_y(_data.Y()); +} + +inline void Set(gz::math::Vector2d *_data, const gz::msgs::Vector2d &_msg) +{ + _data->Set(_msg.x(), _msg.y()); +} + +inline gz::msgs::Vector2d Convert(const gz::math::Vector2d &_data) +{ + gz::msgs::Vector2d ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::Vector2d Convert(const gz::msgs::Vector2d &_msg) +{ + gz::math::Vector2d ret; + Set(&ret, _msg); + return ret; +} +} // namespce +} // namespace gz::msgs +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/Vector3.hh b/core/include/gz/msgs/convert/Vector3.hh new file mode 100644 index 00000000..3a2a096f --- /dev/null +++ b/core/include/gz/msgs/convert/Vector3.hh @@ -0,0 +1,58 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_VECTOR3_HH_ +#define GZ_MSGS_CONVERT_VECTOR3_HH_ + +// Message Headers +#include "gz/msgs/vector3d.pb.h" + +// Data Headers +#include + +namespace gz::msgs { +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE { + +///////////////////////////////// +inline void Set(gz::msgs::Vector3d *_msg, const gz::math::Vector3d &_data) +{ + _msg->set_x(_data.X()); + _msg->set_y(_data.Y()); + _msg->set_z(_data.Z()); +} + +inline void Set(gz::math::Vector3d *_data, const gz::msgs::Vector3d &_msg) +{ + _data->Set(_msg.x(), _msg.y(), _msg.z()); +} + +inline gz::msgs::Vector3d Convert(const gz::math::Vector3d &_data) +{ + gz::msgs::Vector3d ret; + Set(&ret, _data); + return ret; +} + +inline gz::math::Vector3d Convert(const gz::msgs::Vector3d &_msg) +{ + gz::math::Vector3d ret; + Set(&ret, _msg); + return ret; +} +} // namespace +} // namespace gz::msgs +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ diff --git a/core/include/gz/msgs/convert/make_stubs.py b/core/include/gz/msgs/convert/make_stubs.py new file mode 100755 index 00000000..30e2359c --- /dev/null +++ b/core/include/gz/msgs/convert/make_stubs.py @@ -0,0 +1,119 @@ +#!/usr/bin/env python3 + +data = { + "Color": [["gz/msgs/color.pb.h", "gz/math/Color.hh", "gz::msgs::Color", "gz::math::Color"]], + "AxisAlignedBox": [["gz/msgs/axis_aligned_box.pb.h", "gz/math/AxisAlignedBox.hh", "gz::msgs::AxisAlignedBox", "gz::math::AxisAlignedBox"]], + "SphericalCoordinates": [["gz/msgs/spherical_coordinates.pb.h", "gz/math/SphericalCoordinates.hh", "gz::msgs::SphericalCoordinates", "gz::math::SphericalCoordinates"]], + "Inertial": [ + ["gz/msgs/inertial.pb.h", "gz/math/Inertial.hh", "gz::msgs::Inertial", "gz::math::Inertiald"], + ["", "gz/math/MassMatrix3.hh", "gz::msgs::Inertial", "gz::math::MassMatrix3d"] + ], + "Pose": [["gz/msgs/pose.pb.h", "gz/math/Pose3.hh", "gz::msgs::Pose", "gz::math::Pose3d"]], + "Plane": [["gz/msgs/planegeom.pb.h", "gz/math/Plane.hh", "gz::msgs::PlaneGeom", "gz::math::Planed"]], + "Quaternion": [["gz/msgs/quaternion.pb.h", "gz/math/Quaternion.hh", "gz::msgs::Quaternion", "gz::math::Quaterniond"]], + "Vector2": [["gz/msgs/vector2d.pb.h", "gz/math/Vector2.hh", "gz::msgs::Vector2d", "gz::math::Vector2d"]], + "Vector3": [["gz/msgs/vector3d.pb.h", "gz/math/Vector3.hh", "gz::msgs::Vector3d", "gz::math::Vector3d"]], + "StdTypes": [ + ["gz/msgs/time.pb.h", "chrono", "gz::msgs::Time", "std::chrono::steady_clock::duration"], + ["gz/msgs/stringmsg.pb.h", "string", "gz::msgs::StringMsg", "std::string"], + ["gz/msgs/boolean.pb.h", "", "gz::msgs::Boolean", "bool"], + ["gz/msgs/int32.pb.h", "", "gz::msgs::Int32", "int32_t"], + ["gz/msgs/uint32.pb.h", "", "gz::msgs::UInt32", "uint32_t"], + ["gz/msgs/int64.pb.h", "", "gz::msgs::Int64", "int64_t"], + ["gz/msgs/uint64.pb.h", "", "gz::msgs::UInt64", "uint64_t"], + ["gz/msgs/float.pb.h", "", "gz::msgs::Float", "float"], + ["gz/msgs/double.pb.h", "", "gz::msgs::Double", "double"], + ], +} + +template = """/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ +#ifndef GZ_MSGS_CONVERT_{header}_HH_ +#define GZ_MSGS_CONVERT_{header}_HH_ + +#include + +// Message Headers +{msg_headers} + +// Data Headers +{data_headers} + +namespace gz::msgs {{ +// Inline bracket to help doxygen filtering. +inline namespace GZ_MSGS_VERSION_NAMESPACE {{ + +{conversions} + +}} // namespce +}} // namespace gz::msgs + +#endif // GZ_MSGS_CONVERT_VECTOR3_HH_ +""" + +convert_template = """///////////////////////////////// +template<> +inline void Converter<{msg_type}, {data_type}>::Set({msg_type} *_msg, const {data_type} &_data) +{{ +}} + +template<> +inline void Converter<{msg_type}, {data_type}>::Set({data_type} *_data, const {msg_type} &_msg) +{{ +}} + +inline {msg_type} Convert(const {data_type} &_data) +{{ + return Converter<{msg_type}, {data_type}>::Convert(_data); +}} + +inline {data_type} Convert(const {msg_type} &_msg) +{{ + return Converter<{msg_type}, {data_type}>::Convert(_msg); +}} +""" + +headers = [] + +for header, v in data.items(): + msg_headers = [] + data_headers = [] + conversions = [] + + headers.append(f'#include ') + + for entry in v: + msg_header = entry[0] + data_header = entry[1] + msg_type = entry[2] + data_type = entry[3] + + if len(msg_header): + msg_headers.append(f'#include "{msg_header}"') + if len(data_header): + data_headers.append(f'#include <{data_header}>') + conversions.append(convert_template.format(**locals())) + + msg_headers = '\n'.join(sorted(msg_headers)) + data_headers = '\n'.join(sorted(data_headers)) + conversions = '\n'.join(conversions) + + with open(header + '.hh', 'w') as f: + header = header.upper() + f.write(template.format(**locals())) + +print('\n'.join(sorted(headers))) diff --git a/include/gz/msgs/detail/PointCloudPackedUtils.hh b/core/include/gz/msgs/detail/PointCloudPackedUtils.hh similarity index 100% rename from include/gz/msgs/detail/PointCloudPackedUtils.hh rename to core/include/gz/msgs/detail/PointCloudPackedUtils.hh diff --git a/core/include/gz/msgs/detail/dynamic_message_cast.hh b/core/include/gz/msgs/detail/dynamic_message_cast.hh new file mode 100644 index 00000000..de9a3ee4 --- /dev/null +++ b/core/include/gz/msgs/detail/dynamic_message_cast.hh @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * + */ + +#ifndef GZ_MSGS_DETAIL_DYNAMIC_POINTER_CAST_HH_ +#define GZ_MSGS_DETAIL_DYNAMIC_POINTER_CAST_HH_ + +#include + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4100 4512 4127 4068 4244 4267 4251 4146) +#endif +#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +namespace gz::msgs::detail +{ + +/// Cast a base unique pointer to protobuf message type to child type +template +std::unique_ptr +dynamic_message_cast(std::unique_ptr &&_baseMsg) +{ + auto converted = std::unique_ptr{dynamic_cast(_baseMsg.get())}; + if (converted) { + (void) _baseMsg.release(); + } + return converted; +} + +} // namespace gz::msgs::detail + +#endif // GZ_MSGS_DETAIL_DYNAMIC_POINTER_CAST_HH_ diff --git a/core/src/DynamicFactory.cc b/core/src/DynamicFactory.cc new file mode 100644 index 00000000..f372dc15 --- /dev/null +++ b/core/src/DynamicFactory.cc @@ -0,0 +1,144 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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 "DynamicFactory.hh" +#include "gz/utils/Environment.hh" + +namespace { +static constexpr const char * kDescriptorEnv = "GZ_DESCRIPTOR_PATH"; +#ifdef _WIN32 +static constexpr char kEnvironmentVariableSeparator = ';'; +#else +static constexpr char kEnvironmentVariableSeparator = ':'; +#endif + +////////////////////////////////////////////////// +/// \brief split at a one character delimiter to get a vector of something +/// \param[in] _orig The string to split +/// \param[in] _delim a character to split the string at +/// \returns vector of split pieces of the string excluding the delimiter +std::vector split(const std::string &_orig, char _delim) +{ + std::vector pieces; + size_t pos1 = 0; + size_t pos2 = _orig.find(_delim); + while (pos2 != std::string::npos) + { + pieces.push_back(_orig.substr(pos1, pos2-pos1)); + pos1 = pos2+1; + pos2 = _orig.find(_delim, pos2+1); + } + pieces.push_back(_orig.substr(pos1, _orig.size()-pos1)); + return pieces; +} +} // namespace + +namespace gz::msgs { + +////////////////////////////////////////////////// +DynamicFactory::DynamicFactory() +{ + // Try to get the list of paths from an environment variable. + std::string descPaths; + if (gz::utils::env(kDescriptorEnv, descPaths)) { + // Load all the descriptors found in the paths set with GZ_DESCRIPTOR_PATH. + this->LoadDescriptors(descPaths); + } +} + +////////////////////////////////////////////////// +void DynamicFactory::LoadDescriptors(const std::string &_paths) +{ + if (_paths.empty()) + return; + + // Split all the directories containing .desc files. + std::vector descDirs = + split(_paths, kEnvironmentVariableSeparator); + + for (const std::string &descDir : descDirs) + { + for (auto const &dirIter : std::filesystem::directory_iterator{descDir}) + { + // Ignore files without the .desc extension. + if (dirIter.path().extension() != ".desc") + continue; + + std::ifstream ifs(dirIter.path().string(), std::ifstream::in); + if (!ifs.is_open()) + { + std::cerr << "DynamicFactory(): Unable to open [" + << dirIter.path() << "]" + << std::endl; + continue; + } + + google::protobuf::FileDescriptorSet fileDescriptorSet; + if (!fileDescriptorSet.ParseFromIstream(&ifs)) + { + std::cerr << "DynamicFactory(): Unable to parse descriptor set from [" + << dirIter.path() << "]" << std::endl; + continue; + } + + for (const google::protobuf::FileDescriptorProto &fileDescriptorProto : + fileDescriptorSet.file()) + { + if (!pool.BuildFile(fileDescriptorProto)) + { + std::cerr << "DynamicFactory(). Unable to place descriptors from [" + << dirIter.path() + << "] in the descriptor pool" << std::endl; + } + } + } + } +} + +////////////////////////////////////////////////// +DynamicFactory::MessagePtr DynamicFactory::New(const std::string &_msgType) +{ + // Shortcut if the type has been already registered. + auto messageIt = dynamicMsgMap.find(_msgType); + if (messageIt != dynamicMsgMap.end()) + return messageIt ->second(); + + // Nothing to do if we don't know about this type in the descriptor map. + auto descriptor = pool.FindMessageTypeByName(_msgType); + if (!descriptor) + return nullptr; + + google::protobuf::Message *msgPtr( + dynamicMessageFactory.GetPrototype(descriptor)->New()); + + // Create the lambda for registration purposes. + auto f = [msgPtr]() -> MessagePtr + { + MessagePtr ptr(msgPtr->New()); + return ptr; + }; + + // Register the new type for the future. + dynamicMsgMap[_msgType] = f; + + return f(); +} +} // namespace gz::msgs diff --git a/core/src/DynamicFactory.hh b/core/src/DynamicFactory.hh new file mode 100644 index 00000000..e0d0c624 --- /dev/null +++ b/core/src/DynamicFactory.hh @@ -0,0 +1,93 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * +*/ +#ifndef DYNAMIC_FACTORY_HH_ +#define DYNAMIC_FACTORY_HH_ + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4146 4251) +#endif + +#include +#include + +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +#include +#include +#include + + +namespace gz::msgs { + +///////////////////////////////////////////////// +/// \brief A factory class to generate protobuf messages at runtime based on +/// their message descriptors. The location of the .desc files is expected +/// via the GZ_DESCRIPTOR_PATH environment variable. This environment +/// variable expects paths to directories containing .desc files. +/// Any file without the .desc extension will be ignored. +class DynamicFactory +{ + public: using Message = google::protobuf::Message; + public: using MessagePtr = std::unique_ptr; + +#ifdef WIN32 + public: static constexpr char kEnvironmentVariableSeparator = ';'; +#else + public: static constexpr char kEnvironmentVariableSeparator = ':'; +#endif + + ////////////////////////////////////////////////// + /// \brief Constructor. + /// The constructor will try to load all descriptors specified in the + /// GZ_DESCRIPTOR_PATH environment variable. + public: DynamicFactory(); + + ////////////////////////////////////////////////// + /// \brief Load descriptors into the descriptor pool. + /// \param[in] _paths A set of directories containing .desc decriptor files. + /// Each directory should be separated by ":". + public: void LoadDescriptors(const std::string &_paths); + + ////////////////////////////////////////////////// + /// \brief Create a new instance of a message. + /// \param[in] _msgType Type of message to create. + /// \return Pointer to a google protobuf message. Null if the message + /// type could not be handled. + public: MessagePtr New(const std::string &_msgType); + + /// \typedef FactoryFn + /// \brief Prototype for message factory generation + private: using FactoryFn = std::function; + + /// \brief A list of registered message types built at runtime. + /// The key is the message type. The value is a function that returns a + /// std::unique_ptr to a new empty instance of the message or nullptr if + /// the message is not registered. + private: std::map dynamicMsgMap; + + /// \brief We store the descriptors here. + private: google::protobuf::DescriptorPool pool; + + /// \brief Used to create a message from a descriptor. + private: google::protobuf::DynamicMessageFactory dynamicMessageFactory; +}; + +} // namespace gz::msgs +#endif // DYNAMIC_FACTORY_HH_ diff --git a/core/src/Factory.cc b/core/src/Factory.cc new file mode 100644 index 00000000..f11c35ee --- /dev/null +++ b/core/src/Factory.cc @@ -0,0 +1,62 @@ +/* + * Copyright (C) 2016 Open Source Robotics Foundation + * + * 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 "gz/msgs/Factory.hh" +#include + +namespace gz::msgs +{ +///////////////////////////////////////////////// +MessageFactory& Factory::Instance() +{ + static gz::utils::NeverDestroyed instance; + return instance.Access(); +} + +///////////////////////////////////////////////// +void Factory::Register(const std::string &_msgType, + FactoryFn _factoryfn) +{ + Factory::Instance().Register(_msgType, _factoryfn); +} + +///////////////////////////////////////////////// +void Factory::Types(std::vector &_types) +{ + Factory::Instance().Types(_types); +} + +///////////////////////////////////////////////// +Factory::MessagePtr Factory::New(const std::string &_msgType) +{ + return Factory::Instance().New(_msgType); +} + +///////////////////////////////////////////////// +Factory::MessagePtr +Factory::New(const std::string &_msgType, const std::string &_args) +{ + return Factory::Instance().New(_msgType, _args); +} + +///////////////////////////////////////////////// +void Factory::LoadDescriptors(const std::string &_paths) +{ + Factory::Instance().LoadDescriptors(_paths); +} + +} // namespace gz::msgs diff --git a/core/src/MessageFactory.cc b/core/src/MessageFactory.cc new file mode 100644 index 00000000..55d0ac5b --- /dev/null +++ b/core/src/MessageFactory.cc @@ -0,0 +1,118 @@ +/* + * Copyright (C) 2016 Open Source Robotics Foundation + * + * 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. + * +*/ + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4146 4251) +#endif +#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +#include "DynamicFactory.hh" +#include "gz/msgs/MessageFactory.hh" +#include + +namespace gz::msgs +{ + +///////////////////////////////////////////////// +MessageFactory::MessageFactory(): + dynamicFactory(gz::utils::MakeUniqueImpl()) +{ +} + +///////////////////////////////////////////////// +MessageFactory::~MessageFactory() = default; + +///////////////////////////////////////////////// +void MessageFactory::Register(const std::string &_msgType, + FactoryFn _factoryfn) +{ + msgMap[_msgType] = _factoryfn; +} + +///////////////////////////////////////////////// +MessageFactory::MessagePtr MessageFactory::New( + const std::string &_msgType) +{ + std::string type; + + // Convert "gz.msgs." to "gz_msgs.". + if (_msgType.find("gz_msgs.") == 0) + { + type = "gz.msgs." + _msgType.substr(8); + } + else if (_msgType.find(".gz_msgs.") == 0) + { + type = "gz.msgs." + _msgType.substr(9); + } + // Convert ".gz.msgs." to "gz_msgs.". + else if (_msgType.find(".gz.msgs.") == 0) + { + type = "gz.msgs." + _msgType.substr(9); + } + else + { + type = _msgType; + } + + if (msgMap.find(type) != msgMap.end()) + { + // Create a new message if a FactoryFn has been assigned to the message type + return msgMap[type](); + } + else + { + // Check if we have the message descriptor. + return dynamicFactory->New(type); + } +} + +///////////////////////////////////////////////// +MessageFactory::MessagePtr MessageFactory::New( + const std::string &_msgType, const std::string &_args) +{ + std::unique_ptr msg = New(_msgType); + if (msg) + { + google::protobuf::TextFormat::ParseFromString(_args, msg.get()); + } + return msg; +} + +///////////////////////////////////////////////// +void MessageFactory::Types(std::vector &_types) +{ + _types.clear(); + + // Return the list of all known message types. + std::map::const_iterator iter; + for (iter = msgMap.begin(); iter != msgMap.end(); ++iter) + { + _types.push_back(iter->first); + } +} + +///////////////////////////////////////////////// +void MessageFactory::LoadDescriptors(const std::string &_paths) +{ + dynamicFactory->LoadDescriptors(_paths); +} + +} // namespace gz::msgs diff --git a/examples/generating_custom_msgs/CMakeLists.txt b/examples/generating_custom_msgs/CMakeLists.txt new file mode 100644 index 00000000..9c0d3e51 --- /dev/null +++ b/examples/generating_custom_msgs/CMakeLists.txt @@ -0,0 +1,52 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +#============================================================================ +# Initialize the project +#============================================================================ +project(generating_custom_messages VERSION 1.0.0) + +#============================================================================ +# Find gz-cmake +#============================================================================ +find_package(gz-cmake3 REQUIRED) + +find_package(gz-msgs10 REQUIRED) +set(GZ_MSGS_VER ${gz-msgs10_VERSION_MAJOR}) + +# Get the gz-msgs installed messages and generate a library from them +gz_msgs_get_installed_messages( + MESSAGES_PATH_VARIABLE MSGS_PATH + MESSAGES_PROTOS_VARIABLE MSGS_PROTOS) + +gz_msgs_generate_messages( + TARGET gz_msgs_gen + PROTO_PACKAGE "gz.msgs" + MSGS_PATH ${MSGS_PATH} + MSGS_PROTOS ${MSGS_PROTOS}) + +# Example of custom messages that depend on gz.msgs +set(MSGS_PROTOS + ${CMAKE_CURRENT_SOURCE_DIR}/proto/gz/custom_msgs/vector3d.proto) +gz_msgs_generate_messages( + # The cmake target to be generated for libraries/executables to link + TARGET custom_msgs_gen + # The protobuf package to generate (Typically based on the path) + PROTO_PACKAGE "gz.custom_msgs" + # The path to the base directory of the proto files + # All import paths should be relative to this (eg gz/custom_msgs/vector3d.proto) + MSGS_PATH ${CMAKE_CURRENT_SOURCE_DIR}/proto + # List of proto files to generate + MSGS_PROTOS ${MSGS_PROTOS} + # List of message targets this library imports from + DEPENDENCIES gz_msgs_gen) + +add_executable(${PROJECT_NAME} main.cc) + +# Automatically uses whole-archive linking to get all the messages available +target_link_messages(TARGET ${PROJECT_NAME} PUBLIC MSG_TARGETS custom_msgs_gen gz_msgs_gen) + +install(TARGETS ${PROJECT_NAME} + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib + RUNTIME DESTINATION bin +) diff --git a/examples/generating_custom_msgs/README.md b/examples/generating_custom_msgs/README.md new file mode 100644 index 00000000..bf72be2e --- /dev/null +++ b/examples/generating_custom_msgs/README.md @@ -0,0 +1,66 @@ +# Creating custom gz-msgs entries + +The example in this folder demonstrates how to create your own message defintions. + +Most of the setup is the same as the `using_gz_msgs` example, so if you are not familiar, view that first. + +## Creating message definition + +It is best to create a `proto/` folder in your project to hold your message definitions. +Inside of the `proto/` folder, you should construct a file tree that matches your package name. + +For example, for the package `gz.msgs`, we would create `mkdir -p ./gz/msgs` +For example, for the package `gz.custom_msgs`, we would create `mkdir -p ./gz/custom_msgs` +For example, for the package `foo.bar.baz.bing`, we would create `mkdir -p ./foo/bar/baz/bing` + +Inside the last folder is where you will create your message definitions in the `proto` format. +For more information on the format, consult the [language guide](https://protobuf.dev/programming-guides/proto3/) + +Inside of your `.proto` file, you should also specify the package via the package keyword: + +``` +package gz.msgs; + +package gz.custom_msgs; + +package foo.bar.baz.bing; +``` + +Message definitions may also depend on already-specified `gz-msgs` types: + +``` +import "gz/msgs/header.proto" + +message Foo { + gz.msgs.Header header = 1; +} +``` + +## Generating files for custom messages + +Once the message files are specified, they can be generated via the same CMake command as before: + +``` +# Example of custom messages that depend on gz.msgs +set(MSGS_PROTOS + ${CMAKE_CURRENT_SOURCE_DIR}/proto/gz/custom_msgs/vector3d.proto) +gz_msgs_generate_messages( + # The cmake target to be generated for libraries/executables to link + TARGET custom_msgs_gen + # The protobuf package to generate (Typically based on the path) + PROTO_PACKAGE "gz.custom_msgs" + # The path to the base directory of the proto files + # All import paths should be relative to this (eg gz/custom_msgs/vector3d.proto) + MSGS_PATH ${CMAKE_CURRENT_SOURCE_DIR}/proto + # List of proto files to generate + MSGS_PROTOS ${MSGS_PROTOS} + # List of message targets this library imports from + DEPENDENCIES gz_msgs_gen) +``` + +Be sure to link all dependent message targets: + +``` +# Automatically uses whole-archive linking to get all the messages available +target_link_messages(TARGET ${PROJECT_NAME} PUBLIC MSG_TARGETS custom_msgs_gen gz_msgs_gen) +``` diff --git a/examples/generating_custom_msgs/main.cc b/examples/generating_custom_msgs/main.cc new file mode 100644 index 00000000..b123770c --- /dev/null +++ b/examples/generating_custom_msgs/main.cc @@ -0,0 +1,34 @@ +#include +#include + +#include + +// A simple example that demonstrates the use of the message factory +// +// Usage: +// Print text description of original and custom Vector3d msgs. +// ./generating_custom_messages +int main(int argc, char** argv) +{ + (void) argc; + (void) argv; + // Print the text description of the original message + gz::msgs::Vector3d original; + { + auto descriptor = original.GetDescriptor(); + auto fileDescriptor = descriptor->file(); + std::cout << "Name: " << descriptor->full_name() << std::endl; + std::cout << "File: " << fileDescriptor->name() << std::endl << std::endl; + std::cout << descriptor->DebugString() << std::endl; + } + + // Print the text description of the custom message + gz::custom_msgs::Vector3d custom; + { + auto descriptor = custom.GetDescriptor(); + auto fileDescriptor = descriptor->file(); + std::cout << "Name: " << descriptor->full_name() << std::endl; + std::cout << "File: " << fileDescriptor->name() << std::endl << std::endl; + std::cout << descriptor->DebugString() << std::endl; + } +} diff --git a/src/MessageTypes.hh.in b/examples/generating_custom_msgs/proto/gz/custom_msgs/vector3d.proto similarity index 56% rename from src/MessageTypes.hh.in rename to examples/generating_custom_msgs/proto/gz/custom_msgs/vector3d.proto index 081746b2..61c356b0 100644 --- a/src/MessageTypes.hh.in +++ b/examples/generating_custom_msgs/proto/gz/custom_msgs/vector3d.proto @@ -1,5 +1,5 @@ /* - * Copyright (C) 2017 Open Source Robotics Foundation + * Copyright (C) 2023 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,24 +15,18 @@ * */ -/* This file was automatically generated via CMake. - * Do not edit this directly, instead see: - * gz-msgs/src/MessageTypes.hh.in - */ +syntax = "proto3"; +package gz.custom_msgs; -#ifndef GZ_MSGS_MESSAGE_TYPES_HH_ -#define GZ_MSGS_MESSAGE_TYPES_HH_ +import "gz/msgs/header.proto"; -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable: 4100 4512 4127 4068 4244 4267 4251 4146) -#endif +/// An example of a custom Vector3d with fields a, b, and c +message Vector3d +{ + /// \brief Optional header data + gz.msgs.Header header = 1; -@gz_msgs_headers@ - - -#ifdef _MSC_VER -#pragma warning(pop) -#endif - -#endif + double a = 2; + double b = 3; + double c = 4; +} diff --git a/examples/using_gz_msgs/CMakeLists.txt b/examples/using_gz_msgs/CMakeLists.txt new file mode 100644 index 00000000..9184dd06 --- /dev/null +++ b/examples/using_gz_msgs/CMakeLists.txt @@ -0,0 +1,36 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +#============================================================================ +# Initialize the project +#============================================================================ +project(using_gz_msgs VERSION 1.0.0) + +#============================================================================ +# Find gz-cmake +#============================================================================ +find_package(gz-cmake3 REQUIRED) + +find_package(gz-msgs10 REQUIRED) +set(GZ_MSGS_VER ${gz-msgs10_VERSION_MAJOR}) + +# Get the gz-msgs installed messages and generate a library from them +gz_msgs_get_installed_messages( + MESSAGES_PATH_VARIABLE MSGS_PATH + MESSAGES_PROTOS_VARIABLE MSGS_PROTOS) + +gz_msgs_generate_messages( + TARGET gz_msgs_gen + PROTO_PACKAGE "gz.msgs" + MSGS_PATH ${MSGS_PATH} + MSGS_PROTOS ${MSGS_PROTOS}) + +add_executable(${PROJECT_NAME} main.cc) + +# Automatically uses whole-archive linking to get all the messages available +target_link_messages(TARGET ${PROJECT_NAME} PRIVATE MSG_TARGETS gz_msgs_gen) + +install(TARGETS ${PROJECT_NAME} + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib + RUNTIME DESTINATION bin +) diff --git a/examples/using_gz_msgs/README.md b/examples/using_gz_msgs/README.md new file mode 100644 index 00000000..66719b11 --- /dev/null +++ b/examples/using_gz_msgs/README.md @@ -0,0 +1,65 @@ +# Using gz-msgs as part of your project + +With the new message generation pipeline, downstream users of `gz-msgs` must now generate messages as part of their build process. + +The example in this folder demonstrates how to build messages as part of your build. + + +## Finding gz-cmake + +To begin with, in your project `CMakeLists.txt`, you must find `gz-msgs`: + +``` +find_package(gz-msgs10 REQUIRED) +set(GZ_MSGS_VER ${gz-msgs10_VERSION_MAJOR}) +``` + +Once `gz-msgs` is available, there are three main CMake functions to use. + +## Enumerating installed messages + +The first CMake function retrieves the path to the installed `gz-msgs` proto files, as well as the listing of all available messages. +It will populate the variables passed to the arguments when run. + +``` +# Get the gz-msgs installed messages and generate a library from them +gz_msgs_get_installed_messages( + # Root path of the installed gz-msgs proto files + MESSAGES_PATH_VARIABLE MSGS_PATH + # List of paths to each gz-msgs proto file + MESSAGES_PROTOS_VARIABLE MSGS_PROTOS) +``` + +At this point, the `MSGS_PROTOS` variable will contain all available messages. +If you do not need all the messages, the [`list(FILTER)`](https://cmake.org/cmake/help/v3.6/command/list.html) can be used to include/exclude particular messages. + +## Generating messages + +With the list of available messages, we proceed to the generation step: + +``` +gz_msgs_generate_messages( + # Target created for library/executable linking + TARGET gz_msgs_gen + # Protobuf package name, always gz.msgs for installed messages + PROTO_PACKAGE "gz.msgs" + # Base path of the installed files (output of previous step) + MSGS_PATH ${MSGS_PATH} + # List of protos to generate files (output of previous step) + MSGS_PROTOS ${MSGS_PROTOS}) +``` + +This will output a target `gz_msgs_gen` that can be used to link against. + +## Linking messages + +Once the target is generated, it can be either linked via `target_link_libraries` in CMake, or using the custom `target_link_messages` macro. + +`target_link_messages` will perform whole-archive linking, which guarantees that all the message definitions will be visible in the final output, regardless of link-time optimization. + +``` +# Automatically uses whole-archive linking to get all the messages available +target_link_messages(TARGET ${PROJECT_NAME} PRIVATE MSG_TARGETS gz_msgs_gen) +``` + +In general, library linkage to messages should be `PRIVATE`, as we don't install the message library or headers. diff --git a/examples/using_gz_msgs/main.cc b/examples/using_gz_msgs/main.cc new file mode 100644 index 00000000..e81abea4 --- /dev/null +++ b/examples/using_gz_msgs/main.cc @@ -0,0 +1,40 @@ +#include + +#include + +// A simple example that demonstrates the use of the message factory +// +// Usage: +// With no arguments, it will list all known messages +// ./using_gz_msgs +// With an argument, it will display that message, if found +// ./using_gz_msgs gz.msgs.Vector3d +int main(int argc, char** argv) +{ + if (argc == 1) + { + std::vector known_types; + gz::msgs::Factory::Types(known_types); + std::cout << "Known types: " << std::endl; + for (const auto &t: known_types) + { + std::cout << t << std::endl; + } + } + else + { + gz::msgs::Factory::MessagePtr msg = gz::msgs::Factory::New(argv[1]); + if (msg) + { + auto descriptor = msg->GetDescriptor(); + auto fileDescriptor = descriptor->file(); + std::cout << "Name: " << descriptor->full_name() << std::endl; + std::cout << "File: " << fileDescriptor->name() << std::endl << std::endl; + std::cout << descriptor->DebugString() << std::endl; + } + else + { + std::cout << "Couldn't find msg: " << argv[1] << std::endl;; + } + } +} diff --git a/gz-msgs-extras.cmake.in b/gz-msgs-extras.cmake.in new file mode 100644 index 00000000..aceea59d --- /dev/null +++ b/gz-msgs-extras.cmake.in @@ -0,0 +1,78 @@ +# Copyright 2023 Open Source Robotics Foundation, Inc. +# +# 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. + +# copied from gz-msgs/gz-msgs-extras.cmake + +find_package(Python3 REQUIRED COMPONENTS Interpreter) + +include(${@PROJECT_NAME@_DIR}/gz_msgs_string_utils.cmake) +include(${@PROJECT_NAME@_DIR}/gz_msgs_protoc.cmake) +include(${@PROJECT_NAME@_DIR}/gz_msgs_factory.cmake) +include(${@PROJECT_NAME@_DIR}/gz_msgs_generate.cmake) +include(${@PROJECT_NAME@_DIR}/target_link_messages.cmake) + +set(@PROJECT_NAME@_INSTALL_PATH "${@PROJECT_NAME@_DIR}/../../..") +cmake_path(NORMAL_PATH @PROJECT_NAME@_INSTALL_PATH OUTPUT_VARIABLE @PROJECT_NAME@_INSTALL_PATH) +set(PROTOC_NAME "@PROJECT_NAME@_protoc_plugin") +set(PROTO_SCRIPT_NAME "@PROJECT_NAME@_generate.py") +set(FACTORY_SCRIPT_NAME "@PROJECT_NAME@_generate_factory.py") + +set(@PROJECT_NAME@_PROTO_PATH ${@PROJECT_NAME@_INSTALL_PATH}/share/protos) +set(@PROJECT_NAME@_PROTO_GENERATOR_PLUGIN ${@PROJECT_NAME@_INSTALL_PATH}/bin/${PROTOC_NAME}) +set(@PROJECT_NAME@_PROTO_GENERATOR_SCRIPT ${@PROJECT_NAME@_INSTALL_PATH}/bin/${PROTO_SCRIPT_NAME}) +set(@PROJECT_NAME@_FACTORY_GENERATOR_SCRIPT ${@PROJECT_NAME@_INSTALL_PATH}/bin/${FACTORY_SCRIPT_NAME}) + +function(gz_msgs_get_installed_messages) + set(options "") + set(oneValueArgs MESSAGES_PATH_VARIABLE MESSAGES_PROTOS_VARIABLE) + set(multiValueArgs DEPENDS) + + cmake_parse_arguments(get_installed_messages "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) + + set(@PROJECT_NAME@_INSTALL_PATH "${@PROJECT_NAME@_DIR}/../../..") + cmake_path(NORMAL_PATH @PROJECT_NAME@_INSTALL_PATH OUTPUT_VARIABLE @PROJECT_NAME@_INSTALL_PATH) + + set(@PROJECT_NAME@_PROTO_PATH ${@PROJECT_NAME@_INSTALL_PATH}/share/protos) + file (GLOB protos ${@PROJECT_NAME@_PROTO_PATH}/gz/msgs/*.proto) + set(${get_installed_messages_MESSAGES_PROTOS_VARIABLE} ${protos} PARENT_SCOPE) + set(${get_installed_messages_MESSAGES_PATH_VARIABLE} ${@PROJECT_NAME@_PROTO_PATH} PARENT_SCOPE) +endfunction() + +function(gz_msgs_generate_messages) + set(options "") + set(oneValueArgs MSGS_PATH TARGET PROTO_PACKAGE) + set(multiValueArgs MSGS_PROTOS DEPENDENCIES) + + cmake_parse_arguments(generate_messages "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) + gz_msgs_generate_messages_impl( + MSGS_GEN_SCRIPT + ${@PROJECT_NAME@_PROTO_GENERATOR_SCRIPT} + FACTORY_GEN_SCRIPT + ${@PROJECT_NAME@_FACTORY_GENERATOR_SCRIPT} + GZ_PROTOC_PLUGIN + ${@PROJECT_NAME@_PROTO_GENERATOR_PLUGIN} + INPUT_PROTOS + ${generate_messages_MSGS_PROTOS} + PROTO_PACKAGE + ${generate_messages_PROTO_PACKAGE} + PROTO_PATH + ${generate_messages_MSGS_PATH} + MSGS_LIB + @PROJECT_NAME@::@PROJECT_NAME@ + DEPENDENCIES + ${generate_messages_DEPENDENCIES} + TARGET + ${generate_messages_TARGET} + ) +endfunction() diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt deleted file mode 100644 index a35a0475..00000000 --- a/include/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -add_subdirectory(gz) diff --git a/include/gz/CMakeLists.txt b/include/gz/CMakeLists.txt deleted file mode 100644 index bdf8afc6..00000000 --- a/include/gz/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -add_subdirectory(msgs) diff --git a/include/gz/msgs/Factory.hh b/include/gz/msgs/Factory.hh deleted file mode 100644 index 75fdd113..00000000 --- a/include/gz/msgs/Factory.hh +++ /dev/null @@ -1,151 +0,0 @@ -/* - * Copyright (C) 2016 Open Source Robotics Foundation - * - * 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. - * -*/ -#ifndef GZ_MSGS_FACTORY_HH_ -#define GZ_MSGS_FACTORY_HH_ - -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable: 4100 4512 4127 4068 4244 4267 4251 4146) -#endif -#include -#ifdef _MSC_VER -#pragma warning(pop) -#endif - -#include -#include -#include -#include - -#include "gz/msgs/config.hh" -#include "gz/msgs/Export.hh" - -namespace gz -{ - namespace msgs - { - // Inline bracket to help doxygen filtering. - inline namespace GZ_MSGS_VERSION_NAMESPACE { - // - /// \typedef FactoryFn - /// \brief Prototype for message factory generation - typedef std::unique_ptr (*FactoryFn) (); - - /// \class Factory Factory.hh gz/msgs.hh - /// \brief A factory that generates protobuf message based on a string type. - /// This class will also try to load all Protobuf descriptors specified - /// in the GZ_DESCRIPTOR_PATH environment variable on program start. - class GZ_MSGS_VISIBLE Factory - { - /// \brief Register a message. - /// \param[in] _msgType Type of message to register. - /// \param[in] _factoryfn Function that generates the message. - public: static void Register(const std::string &_msgType, - FactoryFn _factoryfn); - - /// \brief Create a new instance of a message. - /// \param[in] _msgType Type of message to create. - /// \return Pointer to a google protobuf message. Null if the message - /// type could not be handled. - public: template - static std::unique_ptr New(const std::string &_msgType) - { - auto msgType = _msgType; - if (msgType.find("ignition") == 0) - { - msgType.replace(0, 8, "gz"); - std::cerr << "Trying to create deprecated message type [" - << _msgType << "]. Using [" << msgType - << "] instead." << std::endl; - } - return std::unique_ptr( - static_cast(New(msgType).release())); - } - - /// \brief Create a new instance of a message. - /// \param[in] _msgType Type of message to create. - /// \param[in] _args Message arguments. This will populate the message. - /// \return Pointer to a google protobuf message. Null if the message - /// type could not be handled. - public: template - static std::unique_ptr New(const std::string &_msgType, - const std::string &_args) - { - auto msgType = _msgType; - if (msgType.find("ignition") == 0) - { - msgType.replace(0, 8, "gz"); - std::cerr << "Trying to create deprecated message type [" - << _msgType << "]. Using [" << msgType - << "] instead." << std::endl; - } - return std::unique_ptr( - static_cast(New(msgType, _args).release())); - } - - /// \brief Create a new instance of a message. - /// \param[in] _msgType Type of message to create. - /// \return Pointer to a google protobuf message. Null if the message - /// type could not be handled. - public: static std::unique_ptr New( - const std::string &_msgType); - - /// \brief Create a new instance of a message. - /// \param[in] _msgType Type of message to create. - /// \param[in] _args Message arguments. This will populate the message. - /// \return Pointer to a google protobuf message. Null if the message - /// type could not be handled. - public: static std::unique_ptr New( - const std::string &_msgType, const std::string &_args); - - /// \brief Get all the message types - /// \param[out] _types Vector of strings of the message types. - public: static void Types(std::vector &_types); - - /// \brief Load a collection of descriptor .desc files. - /// \param[in] _paths A set of directories containing .desc decriptor - /// files. Each directory should be separated by ":". - public: static void LoadDescriptors(const std::string &_paths); - - /// \brief A list of registered message types - private: static std::map *msgMap; - }; - - /// \brief Static message registration macro - /// - /// Use this macro to register messages. - /// \param[in] _msgtype Message type name. - /// \param[in] _classname Class name for message. - #define GZ_REGISTER_STATIC_MSG(_msgtype, _classname) \ - GZ_MSGS_VISIBLE \ - std::unique_ptr New##_classname() \ - { \ - return std::unique_ptr(\ - new gz::msgs::_classname); \ - } \ - class GZ_MSGS_VISIBLE GzMsg##_classname \ - { \ - public: GzMsg##_classname() \ - { \ - gz::msgs::Factory::Register(_msgtype, New##_classname);\ - } \ - }; \ - static GzMsg##_classname GzMessagesInitializer##_classname; - } - } -} -#endif diff --git a/include/gz/msgs/Filesystem.hh b/include/gz/msgs/Filesystem.hh deleted file mode 100644 index 9fa6ef05..00000000 --- a/include/gz/msgs/Filesystem.hh +++ /dev/null @@ -1,93 +0,0 @@ -/* - * Copyright 2018 Open Source Robotics Foundation - * - * 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. - * - */ - -#ifndef GZ_MSGS_FILESYSTEM_HH_ -#define GZ_MSGS_FILESYSTEM_HH_ - -#include -#include - -#include -#include - -namespace gz -{ - namespace msgs - { - /// \brief Options for how to handle errors that occur in functions that - /// manipulate the filesystem. - enum FilesystemWarningOp - { - /// \brief Errors that occur during filesystem manipulation should be - /// logged as warnings using gzwarn. (Recommended) - FSWO_LOG_WARNINGS = 0, - - /// \brief Errors that occur during filesystem manipulation should not be - /// logged. The user will be responsible for checking the system's error - /// flags. - FSWO_SUPPRESS_WARNINGS - }; - - // /// \internal - class DirIterPrivate; - - /// \class DirIter Filesystem.hh - /// \brief A class for iterating over all items in a directory. - class GZ_MSGS_VISIBLE DirIter - { - /// \brief Constructor. - /// \param[in] _in Directory to iterate over. - public: explicit DirIter(const std::string &_in); - - /// \brief Constructor for end element. - public: DirIter(); - - /// \brief Dereference operator; returns current directory record. - /// \return A string representing the entire path of the directory record. - public: std::string operator*() const; - - /// \brief Pre-increment operator; moves to next directory record. - /// \return This iterator. - public: const DirIter& operator++(); - - /// \brief Comparison operator to see if this iterator is at the - /// same point as another iterator. - /// \param[in] _other The other iterator to compare against. - /// \return true if the iterators are equal, false otherwise. - public: bool operator!=(const DirIter &_other) const; - - /// \brief Destructor - public: ~DirIter(); - - /// \brief Move to the next directory record, skipping . and .. records. - private: void Next(); - - /// \brief Set the internal variable to the empty string. - private: void SetInternalEmpty(); - - /// \brief Close an open directory handle. - private: void CloseHandle(); - - GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING - /// \brief Private data. - private: std::unique_ptr dataPtr; - GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING - }; - } -} - -#endif diff --git a/include/gz/msgs/Utility.hh b/include/gz/msgs/Utility.hh deleted file mode 100644 index b737da96..00000000 --- a/include/gz/msgs/Utility.hh +++ /dev/null @@ -1,500 +0,0 @@ -/* - * Copyright (C) 2016 Open Source Robotics Foundation - * - * 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. - * -*/ -#ifndef GZ_MSGS_UTILITY_HH_ -#define GZ_MSGS_UTILITY_HH_ - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "gz/msgs/config.hh" -#include "gz/msgs/Export.hh" -#include "gz/msgs/MessageTypes.hh" - -/// \file Utility.hh -/// \brief Utility functions that support conversion between message type -/// and Gazebo Math types. - -namespace gz -{ - namespace msgs - { - // Inline bracket to help doxygen filtering. - inline namespace GZ_MSGS_VERSION_NAMESPACE { - // - /// \brief Convert a msgs::Vector3d to a gz::math::Vector - /// \param[in] _v The vector to convert - /// \return A gz::math::Vector3d object - GZ_MSGS_VISIBLE - gz::math::Vector3d Convert(const msgs::Vector3d &_v); - - /// \brief Convert a msgs::Vector2d to a gz::math::Vector2d - /// \param[in] _v The vector2 to convert - /// \return A gz::math::Vector2d object - GZ_MSGS_VISIBLE - gz::math::Vector2d Convert(const msgs::Vector2d &_v); - - /// \brief Convert a msgs::Quaternion to a gz::math::Quaterniond - /// \param[in] _q The quaternion to convert - /// \return A gz::math::Quaterniond object - GZ_MSGS_VISIBLE - gz::math::Quaterniond Convert(const msgs::Quaternion &_q); - - /// \brief Convert a msgs::Pose to a gz::math::Pose3d - /// \param[in] _p The pose to convert - /// \return A gz::math::Pose3d object - GZ_MSGS_VISIBLE - gz::math::Pose3d Convert(const msgs::Pose &_p); - - /// \brief Convert a msgs::Color to a math::Color - /// \param[in] _c The color to convert - /// \return A math::Color object - GZ_MSGS_VISIBLE - math::Color Convert(const msgs::Color &_c); - - /// \brief Convert a msgs::PlaneGeom to a gz::math::Planed - /// \param[in] _p The plane to convert - /// \return A gz::math::Planed object - GZ_MSGS_VISIBLE - gz::math::Planed Convert(const msgs::PlaneGeom &_p); - - /// \brief Convert a msgs::Inertial to a gz::math::Inertiald - /// \param[in] _i The inertial to convert - /// \return A gz::math::Inertiald object - GZ_MSGS_VISIBLE - math::Inertiald Convert(const msgs::Inertial &_i); - - /// \brief Convert a msgs::SphericalCoordinates to an - /// gz::math::SphericalCoordinates - /// \param[in] _coord The spherical coordinates to convert - /// \return A gz::math::SphericalCoordinates object - GZ_MSGS_VISIBLE - math::SphericalCoordinates Convert( - const msgs::SphericalCoordinates &_coord); - - /// \brief Convert a msgs::AxisAlignedBox to an - /// gz::math::AxisAlignedBox - /// \param[in] _b The axis aligned box to convert - /// \return A gz::math::AxisAlignedBox object - GZ_MSGS_VISIBLE - math::AxisAlignedBox Convert(const msgs::AxisAlignedBox &_b); - - /// \brief Convert gz::math::AxisAlignedBox to - /// msgs::AxisAlignedBox. - /// \param[in] _b The axis aligned box to convert - /// \return A gz::math::AxisAlignedBox object - GZ_MSGS_VISIBLE - msgs::AxisAlignedBox Convert(const math::AxisAlignedBox &_b); - - /// \brief Convert a msgs::StringMsg to an std::string - /// \param[in] _m The message to convert - /// \return An std::string object - GZ_MSGS_VISIBLE - std::string Convert(const msgs::StringMsg &_m); - - /// \brief Convert a msgs::Boolean to a bool - /// \param[in] _m The message to convert - /// \return An bool object - GZ_MSGS_VISIBLE - bool Convert(const msgs::Boolean &_m); - - /// \brief Convert a msgs::Int32 to an int32_t - /// \param[in] _m The message to convert - /// \return An int32_t object - GZ_MSGS_VISIBLE - int32_t Convert(const msgs::Int32 &_m); - - /// \brief Convert a msgs::UInt32 to a uint32_t - /// \param[in] _m The message to convert - /// \return An uint32_t object - GZ_MSGS_VISIBLE - uint32_t Convert(const msgs::UInt32 &_m); - - /// \brief Convert a msgs::Int64 to an int64_t - /// \param[in] _m The message to convert - /// \return An int64_t object - GZ_MSGS_VISIBLE - int64_t Convert(const msgs::Int64 &_m); - - /// \brief Convert a msgs::UInt64 to a uint64_t - /// \param[in] _m The message to convert - /// \return An uint64_t object - GZ_MSGS_VISIBLE - uint64_t Convert(const msgs::UInt64 &_m); - - /// \brief Convert a msgs::Double to a double - /// \param[in] _m The message to convert - /// \return An double object - GZ_MSGS_VISIBLE - double Convert(const msgs::Double &_m); - - /// \brief Convert a msgs::Float to a float - /// \param[in] _m The message to convert - /// \return An float object - GZ_MSGS_VISIBLE - float Convert(const msgs::Float &_m); - - /// \brief Convert a msgs::Time to a std::chrono::steady_clock::duration - /// \param[in] _time The message to convert - /// \return A std::chrono::steady_clock::duration object - GZ_MSGS_VISIBLE - std::chrono::steady_clock::duration Convert(const msgs::Time &_time); - - /// \brief Convert a gz::math::Vector3d to a msgs::Vector3d - /// \param[in] _v The vector to convert - /// \return A msgs::Vector3d object - GZ_MSGS_VISIBLE - msgs::Vector3d Convert(const gz::math::Vector3d &_v); - - /// \brief Convert a gz::math::Vector2d to a msgs::Vector2d - /// \param[in] _v The vector to convert - /// \return A msgs::Vector2d object - GZ_MSGS_VISIBLE - msgs::Vector2d Convert(const gz::math::Vector2d &_v); - - /// \brief Convert a gz::math::Quaterniond to a msgs::Quaternion - /// \param[in] _q The quaternion to convert - /// \return A msgs::Quaternion object - GZ_MSGS_VISIBLE - msgs::Quaternion Convert(const gz::math::Quaterniond &_q); - - /// \brief Convert a gz::math::Pose3d to a msgs::Pose - /// \param[in] _p The pose to convert - /// \return A msgs::Pose object - GZ_MSGS_VISIBLE - msgs::Pose Convert(const gz::math::Pose3d &_p); - - /// \brief Convert a math::Color to a msgs::Color - /// \param[in] _c The color to convert - /// \return A msgs::Color object - GZ_MSGS_VISIBLE - msgs::Color Convert(const math::Color &_c); - - /// \brief Convert an math::Inertiald to a msgs::Inertial - /// \param[in] _i The Inertiald to convert - /// \return A msgs::Inertial object - GZ_MSGS_VISIBLE - msgs::Inertial Convert(const math::Inertiald &_i); - - /// \brief Convert an math::MassMatrix3d to a msgs::Inertial - /// \param[in] _m The MassMatrix3d to convert - /// \return A msgs::Inertial object - GZ_MSGS_VISIBLE - msgs::Inertial Convert(const math::MassMatrix3d &_m); - - /// \brief Convert an math::SphericalCoordinates to a - /// msgs::SphericalCoordinates - /// \param[in] _coord The SphericalCoordinates to convert - /// \return A msgs::SphericalCoordinates object - GZ_MSGS_VISIBLE - msgs::SphericalCoordinates Convert( - const math::SphericalCoordinates &_coord); - - /// \brief Convert a gz::math::Planed to a msgs::PlaneGeom - /// \param[in] _p The plane to convert - /// \return A msgs::PlaneGeom object - GZ_MSGS_VISIBLE - msgs::PlaneGeom Convert(const gz::math::Planed &_p); - - /// \brief Convert an std::string to a msgs::StringMsg - /// \param[in] _s The string to convert - /// \return A msgs::StringMsg object - GZ_MSGS_VISIBLE - msgs::StringMsg Convert(const std::string &_s); - - /// \brief Convert a bool to a msgs::Boolean - /// \param[in] _b The bool to convert - /// \return A msgs::Boolean object - GZ_MSGS_VISIBLE - msgs::Boolean Convert(const bool &_b); - - /// \brief Convert an int32_t to a msgs::Int32 - /// \param[in] _i The int32_t to convert - /// \return A msgs::Int32 object - GZ_MSGS_VISIBLE - msgs::Int32 Convert(const int32_t &_i); - - /// \brief Convert a uint32_t to a msgs::UInt32 - /// \param[in] _u The uint32_t to convert - /// \return A msgs::UInt32 object - GZ_MSGS_VISIBLE - msgs::UInt32 Convert(const uint32_t &_u); - - /// \brief Convert an int64_t to a msgs::Int64 - /// \param[in] _i The int64_t to convert - /// \return A msgs::Int64 object - GZ_MSGS_VISIBLE - msgs::Int64 Convert(const int64_t &_i); - - /// \brief Convert a uint64_t to a msgs::UInt64 - /// \param[in] _u The uint64_t to convert - /// \return A msgs::UInt64 object - GZ_MSGS_VISIBLE - msgs::UInt64 Convert(const uint64_t &_u); - - /// \brief Convert a double to a msgs::Double - /// \param[in] _d The double to convert - /// \return A msgs::Double object - GZ_MSGS_VISIBLE - msgs::Double Convert(const double &_d); - - /// \brief Convert a float to a msgs::Float - /// \param[in] _f The float to convert - /// \return A msgs::Float object - GZ_MSGS_VISIBLE - msgs::Float Convert(const float &_f); - - /// \brief Convert a std::chrono::steady_clock::duration to a msgs::Time - /// \param[in] _time_point The std::chrono::system_clock::duration to - /// convert - /// \return A msgs::Time object - GZ_MSGS_VISIBLE - msgs::Time Convert( - const std::chrono::steady_clock::duration &_time_point); - - /// \brief Convert a string to a msgs::Joint::Type enum. - /// \param[in] _str Joint type string. - /// \return A msgs::Joint::Type enum. Defaults to REVOLUTE - /// if _str is unrecognized. - GZ_MSGS_VISIBLE - msgs::Joint::Type ConvertJointType(const std::string &_str); - - /// \brief Convert a msgs::Joint::Type to a string. - /// \param[in] _type A msgs::Joint::Type enum. - /// \return Joint type string. Returns "unknown" if - /// _type is unrecognized. - GZ_MSGS_VISIBLE - std::string ConvertJointType(const msgs::Joint::Type &_type); - - /// \brief Convert a string to a msgs::Geometry::Type enum. - /// \param[in] _str Geometry type string. - /// \return A msgs::Geometry::Type enum. - GZ_MSGS_VISIBLE - msgs::Geometry::Type ConvertGeometryType(const std::string &_str); - - /// \brief Convert a msgs::Geometry::Type to a string. - /// \param[in] _type A msgs::Geometry::Type enum. - /// \return Geometry type string. - GZ_MSGS_VISIBLE - std::string ConvertGeometryType(const msgs::Geometry::Type _type); - - /// \brief Convert a string to a msgs::PixelFormatType enum. - /// \param[in] _str PixelFormatType string. - /// \return A msgs::PixelFormatType enum. - GZ_MSGS_VISIBLE - msgs::PixelFormatType ConvertPixelFormatType(const std::string &_str); - - /// \brief Convert a PixelFormatType to a string. This can be used for - /// debugging purposes. - // \param[in] _t PixelFormatType enum value. - /// \return String version of PixelFormatType. - GZ_MSGS_VISIBLE - std::string ConvertPixelFormatType(const msgs::PixelFormatType &_t); - - /// \brief Convert a string to a msgs::Material::ShaderType enum. - /// \param[in] _str Shader type string. - /// \return A msgs::Material::ShaderType enum. Defaults to VERTEX - /// if _str is unrecognized. - GZ_MSGS_VISIBLE - msgs::Material::ShaderType ConvertShaderType(const std::string &_str); - - /// \brief Convert a msgs::ShaderType to a string. - /// \param[in] _type A msgs::ShaderType enum. - /// \return Shader type string. Returns "unknown" if - /// _type is unrecognized. - GZ_MSGS_VISIBLE - std::string ConvertShaderType(const msgs::Material::ShaderType &_type); - - /// \brief Set a msgs::Vector3d from a gz::math::Vector3d - /// \param[out] _pt A msgs::Vector3d pointer - /// \param[in] _v A gz::math::Vector3d reference - GZ_MSGS_VISIBLE - void Set(msgs::Vector3d *_pt, const gz::math::Vector3d &_v); - - /// \brief Set a msgs::Vector2d from a gz::math::Vector2d - /// \param[out] _pt A msgs::Vector2d pointer - /// \param[in] _v A gz::math::Vector2d reference - GZ_MSGS_VISIBLE - void Set(msgs::Vector2d *_pt, const gz::math::Vector2d &_v); - - /// \brief Set a msgs::Quaternion from a gz::math::Quaterniond - /// \param[out] _q A msgs::Quaternion pointer - /// \param[in] _v A gz::math::Quaterniond reference - GZ_MSGS_VISIBLE - void Set(msgs::Quaternion *_q, const gz::math::Quaterniond &_v); - - /// \brief Set a msgs::Pose from a gz::math::Pose3d - /// \param[out] _p A msgs::Pose pointer - /// \param[in] _v A gz::math::Pose3d reference - GZ_MSGS_VISIBLE - void Set(msgs::Pose *_p, const gz::math::Pose3d &_v); - - /// \brief Set a msgs::Color from a math::Color - /// \param[out] _c A msgs::Color pointer - /// \param[in] _v A math::Color reference - GZ_MSGS_VISIBLE - void Set(msgs::Color *_c, const math::Color &_v); - - /// \brief Set a msgs::Inertial from an math::Inertiald - /// \param[out] _i A msgs::Inertial pointer - /// \param[in] _m An math::Inertiald reference - GZ_MSGS_VISIBLE - void Set(msgs::Inertial *_i, const math::Inertiald &_m); - - /// \brief Set a msgs::Inertial from an math::MassMatrix3d - /// \param[out] _i A msgs::Inertial pointer - /// \param[in] _m An math::MassMatrix3d reference - GZ_MSGS_VISIBLE - void Set(msgs::Inertial *_i, const math::MassMatrix3d &_m); - - /// \brief Set a msgs::SphericalCoordinates from a - /// math::SphericalCoordinates - /// \param[out] _sc A msgs::SphericalCoordinates pointer - /// \param[in] _m An math::SphericalCoordinates reference - GZ_MSGS_VISIBLE - void Set(msgs::SphericalCoordinates *_sc, - const math::SphericalCoordinates &_m); - - /// \brief Set a msgs::Plane from a gz::math::Planed - /// \param[out] _p A msgs::Plane pointer - /// \param[in] _v A gz::math::Planed reference - GZ_MSGS_VISIBLE - void Set(msgs::PlaneGeom *_p, const gz::math::Planed &_v); - - /// \brief Set a msgs::StringMsg from an std::string - /// \param[out] _p A msgs::StringMsg pointer - /// \param[in] _v An std::string reference - GZ_MSGS_VISIBLE - void Set(msgs::StringMsg *_p, const std::string &_v); - - /// \brief Set a msgs::Boolean from a bool - /// \param[out] _p A msgs::Boolean pointer - /// \param[in] _v An bool reference - GZ_MSGS_VISIBLE - void Set(msgs::Boolean *_p, const bool &_v); - - /// \brief Set a msgs::Int32 from an int32_t - /// \param[out] _p A msgs::Int32 pointer - /// \param[in] _v An int32_t reference - GZ_MSGS_VISIBLE - void Set(msgs::Int32 *_p, const int32_t &_v); - - /// \brief Set a msgs::UInt32 from a uint32_t - /// \param[out] _p A msgs::UInt32 pointer - /// \param[in] _v An uint32_t reference - GZ_MSGS_VISIBLE - void Set(msgs::UInt32 *_p, const uint32_t &_v); - - /// \brief Set a msgs::Int64 from an int64_t - /// \param[out] _p A msgs::Int64 pointer - /// \param[in] _v An int64_t reference - GZ_MSGS_VISIBLE - void Set(msgs::Int64 *_p, const int64_t &_v); - - /// \brief Set a msgs::UInt64 from an uint64_t - /// \param[out] _p A msgs::UInt64 pointer - /// \param[in] _v An uint64_t reference - GZ_MSGS_VISIBLE - void Set(msgs::UInt64 *_p, const uint64_t &_v); - - /// \brief Set a msgs::Double from a double - /// \param[out] _p A msgs::Double pointer - /// \param[in] _v An double reference - GZ_MSGS_VISIBLE - void Set(msgs::Double *_p, const double &_v); - - /// \brief Set a msgs::Float from a float - /// \param[out] _p A msgs::Float pointer - /// \param[in] _v An float reference - GZ_MSGS_VISIBLE - void Set(msgs::Float *_p, const float &_v); - - /// \brief Set a msgs::AxisAlignedBox from a math::AxisAlignedBox - /// \param[out] _b A msgs::AxisAlignedBox pointer - /// \param[in] _v An math::AxisAlignedBox reference - GZ_MSGS_VISIBLE - void Set(msgs::AxisAlignedBox *_b, const math::AxisAlignedBox &_v); - - /// \brief This function will set the header and field members of - /// a PointCloudPacked message. This will clear existing values in the - /// PointCloudPacked field and header. - /// \param[out] _msg The message to initialize. - /// \param[in] _frameId Name of the "frame_id". This will be stored as - /// key = "frame_id", value = _frameId in the message header. - /// \param[in] _memoryAligned If true, then each pair in the _fields - /// vector will be aligned at word (sizeof(size_t)) boundaries. - /// Additionally, the `point_step` of the _msg will be set to the - /// nearest word boundary. - /// \param[in] _fields The fields to add to the message. The following - /// strings are reserved, and will generate a set of fields - /// automatically. - /// - /// * "xyz" : This will add the "x", "y", and "z" fields. - GZ_MSGS_VISIBLE - void InitPointCloudPacked(msgs::PointCloudPacked &_msg, - const std::string &_frameId, bool _memoryAligned, - const std::vector> &_fields); - - /// \brief Convert a Discovery::Type to a string. This can be used for - /// debugging purposes. - // \param[in] _t Type of the discovery message. - /// \return String version of Discovery::Type. - GZ_MSGS_VISIBLE - std::string ToString(const msgs::Discovery::Type &_t); - - /// \brief Convert the contents of a model.config file, in the form of - /// an XML string, to a FuelMetadata message. - /// - /// Only the latest versioned model is added to the meta data message. - /// - /// The `` and `` tags are ignored. - /// - /// \param[in] _modelConfigStr A string containing XML data that matches - /// the model.config format. - /// \param[out] _meta The message that receives the converted data. - /// \return True if the conversion was successful. - GZ_MSGS_VISIBLE - bool ConvertFuelMetadata(const std::string &_modelConfigStr, - msgs::FuelMetadata &_meta); - - /// \brief Convert a FuelMetadata message to a string containing XML - /// data that matches the model.config format. - /// - /// The model.config format contains only a subset of the information in - /// a metadata message. The extra information in the metadata message is - /// discarded. - /// - /// \param[in] _meta The FuelMetadata message to convert. - /// \param[out] _modelConfigStr XML string containing the converted - /// message data. - /// \return True if the conversion was successful. - GZ_MSGS_VISIBLE - bool ConvertFuelMetadata(const msgs::FuelMetadata &_meta, - std::string &_modelConfigStr); - } - } -} -#endif diff --git a/proto/CMakeLists.txt b/proto/CMakeLists.txt index 86cad236..ab89ab77 100644 --- a/proto/CMakeLists.txt +++ b/proto/CMakeLists.txt @@ -1,5 +1,5 @@ install( DIRECTORY gz - DESTINATION "${GZ_INCLUDE_INSTALL_DIR_FULL}" + DESTINATION share/protos COMPONENT proto FILES_MATCHING PATTERN "*.proto") diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt deleted file mode 100644 index 6440599d..00000000 --- a/src/CMakeLists.txt +++ /dev/null @@ -1,283 +0,0 @@ -################################################## -# Build a custom protoc plugin -gz_add_executable(gz_msgs_gen Generator.cc generator_main.cc) -target_link_libraries(gz_msgs_gen - protobuf::libprotoc - protobuf::libprotobuf) -target_include_directories(gz_msgs_gen PRIVATE ${PROTOBUF_INCLUDE_DIR}) -target_compile_features(gz_msgs_gen PRIVATE ${GZ_CXX_11_FEATURES}) - -if (UNIX) - target_link_libraries(gz_msgs_gen pthread) -endif() - -if(INSTALL_GZ_MSGS_GEN_EXECUTABLE) - set_target_properties(gz_msgs_gen PROPERTIES VERSION ${PROJECT_VERSION_FULL}) - install(TARGETS gz_msgs_gen DESTINATION ${GZ_BIN_INSTALL_DIR}) - - # TODO(chapulina) Deprecated. Remove on v10. - install(FILES $ DESTINATION ${GZ_BIN_INSTALL_DIR} RENAME ign_msgs_gen PERMISSIONS OWNER_EXECUTE) -endif() - -find_package(Python3 REQUIRED COMPONENTS Interpreter) - -################################################## -# A function that calls protoc on a protobuf file -# Options: -# GENERATE_RUBY - generates ruby code for the message if specified -# GENERATE_CPP - generates c++ code for the message if specified -# One value arguments: -# PROTO_PACKAGE - Protobuf package the file belongs to (e.g. ".gz.msgs") -# PROTOC_EXEC - Path to protoc -# INPUT_PROTO - Path to the input .proto file -# OUTPUT_CPP_DIR - Path where C++ files are saved -# OUTPUT_RUBY_DIR - Path where Ruby files are saved -# OUTPUT_INCLUDES - A CMake variable name containing a list that the C++ header path should be appended to -# OUTPUT_CPP_HH_VAR - A CMake variable name containing a list that the C++ header path should be appended to -# OUTPUT_GZ_CPP_HH_VAR - A CMake variable name containing a list that the C++ header path should be appended to -# OUTPUT_CPP_CC_VAR - A Cmake variable name containing a list that the C++ source path should be appended to -# OUTPUT_RUBY_VAR - A Cmake variable name containing a list that the ruby file should be apenned to -# Multi value arguments -# PROTO_PATH - Passed to protoc --proto_path -function(gz_msgs_protoc) - set(options GENERATE_RUBY GENERATE_CPP) - set(oneValueArgs - PROTO_PACKAGE - PROTOC_EXEC - INPUT_PROTO - OUTPUT_CPP_DIR - OUTPUT_RUBY_DIR - OUTPUT_INCLUDES - OUTPUT_CPP_HH_VAR - OUTPUT_GZ_CPP_HH_VAR - OUTPUT_DETAIL_CPP_HH_VAR - OUTPUT_CPP_CC_VAR - OUTPUT_RUBY_VAR) - set(multiValueArgs PROTO_PATH) - - cmake_parse_arguments(gz_msgs_protoc "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) - - get_filename_component(ABS_FIL ${gz_msgs_protoc_INPUT_PROTO} ABSOLUTE) - get_filename_component(FIL_WE ${gz_msgs_protoc_INPUT_PROTO} NAME_WE) - - set(protoc_args) - set(output_files) - - set(proto_package_dir ".") - if(gz_msgs_protoc_PROTO_PACKAGE) - string(REPLACE "." "/" proto_package_dir ${gz_msgs_protoc_PROTO_PACKAGE}) - endif() - - if(gz_msgs_protoc_GENERATE_CPP) - # Full path to generated header (${PROJECT_BINARY_DIR}/include/gz/msgs/foo.pb.h) - set(output_header "${gz_msgs_protoc_OUTPUT_CPP_DIR}${proto_package_dir}/${FIL_WE}.pb.h") - # Full path to generated detail header (${PROJECT_BINARY_DIR}/include/gz/msgs/details/foo.pb.h) - set(output_detail_header "${gz_msgs_protoc_OUTPUT_CPP_DIR}${proto_package_dir}/details/${FIL_WE}.pb.h") - # Full path to generated source (${PROJECT_BINARY_DIR}/include/foo.pb.cc) - set(output_source "${gz_msgs_protoc_OUTPUT_CPP_DIR}${proto_package_dir}/${FIL_WE}.pb.cc") - - # Generate a clean relative path (gz/msgs/foo.pb.h) - string(REPLACE "${PROJECT_BINARY_DIR}/include/" "" output_include ${output_header}) - list(APPEND ${gz_msgs_protoc_OUTPUT_INCLUDES} "${output_include}") - - list(APPEND ${gz_msgs_protoc_OUTPUT_CPP_HH_VAR} ${output_header}) - list(APPEND ${gz_msgs_protoc_OUTPUT_CPP_CC_VAR} ${output_source}) - list(APPEND ${gz_msgs_protoc_OUTPUT_GZ_CPP_HH_VAR} ${output_ign_header}) - list(APPEND ${gz_msgs_protoc_OUTPUT_DETAIL_CPP_HH_VAR} ${output_detail_header}) - - list(APPEND output_files ${output_header}) - list(APPEND output_files ${output_detail_header}) - list(APPEND output_files ${output_ign_header}) - list(APPEND output_files ${output_source}) - - set(${gz_msgs_protoc_OUTPUT_INCLUDES} ${${gz_msgs_protoc_OUTPUT_INCLUDES}} PARENT_SCOPE) - set(${gz_msgs_protoc_OUTPUT_GZ_CPP_HH_VAR} ${${gz_msgs_protoc_OUTPUT_GZ_CPP_HH_VAR}} PARENT_SCOPE) - set(${gz_msgs_protoc_OUTPUT_DETAIL_CPP_HH_VAR} ${${gz_msgs_protoc_OUTPUT_DETAIL_CPP_HH_VAR}} PARENT_SCOPE) - set(${gz_msgs_protoc_OUTPUT_CPP_HH_VAR} ${${gz_msgs_protoc_OUTPUT_CPP_HH_VAR}} PARENT_SCOPE) - set(${gz_msgs_protoc_OUTPUT_CPP_CC_VAR} ${${gz_msgs_protoc_OUTPUT_CPP_CC_VAR}} PARENT_SCOPE) - endif() - - if(gz_msgs_protoc_GENERATE_RUBY) - file(MAKE_DIRECTORY ${gz_msgs_protoc_OUTPUT_RUBY_DIR}) - set(output_ruby "${gz_msgs_protoc_OUTPUT_RUBY_DIR}${proto_package_dir}/${FIL_WE}_pb.rb") - list(APPEND ${gz_msgs_protoc_OUTPUT_RUBY_VAR} ${output_ruby}) - list(APPEND output_files ${output_ruby}) - list(APPEND protoc_args "--ruby_out=${gz_msgs_protoc_OUTPUT_RUBY_DIR}") - set(${gz_msgs_protoc_OUTPUT_RUBY_VAR} ${${gz_msgs_protoc_OUTPUT_RUBY_VAR}} PARENT_SCOPE) - endif() - - - set(GENERATE_ARGS - --protoc-exec "$" - --gz-generator-bin "${GZ_MSGS_GEN_EXECUTABLE}" - --proto-path "${gz_msgs_protoc_PROTO_PATH}" - --input-path "${ABS_FIL}" - ) - - if(${gz_msgs_protoc_GENERATE_CPP}) - list(APPEND GENERATE_ARGS - --generate-cpp - --output-cpp-path "${gz_msgs_protoc_OUTPUT_CPP_DIR}") - endif() - - if(${gz_msgs_protoc_GENERATE_RUBY}) - list(APPEND GENERATE_ARGS - --generate-ruby - --output-ruby-path "${gz_msgs_protoc_OUTPUT_RUBY_DIR}") - endif() - - add_custom_command( - OUTPUT ${output_files} - COMMAND Python3::Interpreter - ARGS tools/gz_msgs_generate.py ${GENERATE_ARGS} - DEPENDS - ${ABS_FIL} - gz_msgs_gen - # While the script is executed in the source directory, it does not write - # to the source tree. All outputs are stored in the build directory. - WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} - COMMENT "Running protoc on ${gz_msgs_protoc_INPUT_PROTO}" - VERBATIM - ) - -endfunction() - - -################################################## -file (GLOB proto_files ${PROJECT_SOURCE_DIR}/proto/gz/msgs/*.proto) - -foreach(proto_file ${proto_files}) - gz_msgs_protoc( - PROTO_PACKAGE - .gz.msgs - GENERATE_CPP - GENERATE_RUBY - INPUT_PROTO - ${proto_file} - PROTOC_EXEC - protobuf::protoc - OUTPUT_CPP_DIR - "${PROJECT_BINARY_DIR}/include" - OUTPUT_RUBY_DIR - "${PROJECT_BINARY_DIR}/ruby" - OUTPUT_INCLUDES - gen_includes - OUTPUT_CPP_HH_VAR - gen_headers - OUTPUT_DETAIL_CPP_HH_VAR - gen_detail_headers - OUTPUT_GZ_CPP_HH_VAR - gen_ign_headers - OUTPUT_CPP_CC_VAR - gen_sources - OUTPUT_RUBY_VAR - gen_ruby_scripts - PROTO_PATH - "${PROJECT_SOURCE_DIR}/proto") -endforeach() - -if(NOT MSVC) - # -Wno-switch-default flags is required for suppressing a warning in some of - # the generated protobuf files. - set_source_files_properties(${gen_sources} COMPILE_FLAGS -Wno-switch-default) -endif() - -if(MSVC) - # Warning #4251 is the "dll-interface" warning that tells you when types used - # by a class are not being exported. These generated source files have private - # members that don't get exported, so they trigger this warning. However, the - # warning is not important since those members do not need to be interfaced - # with. - set_source_files_properties(${gen_sources} COMPILE_FLAGS "/wd4251 /wd4146") - # Fix for protobuf 3.12 - allow big object files - add_definitions(/bigobj) -endif() - -set_source_files_properties(${gen_headers} ${gen_ign_headers} ${gen_detail_headers} ${gen_sources} ${gen_ruby_scripts} - PROPERTIES GENERATED TRUE) - -message(STATUS "Installing Ruby messages to ${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/ruby/gz/${GZ_DESIGNATION}${PROJECT_VERSION_MAJOR}") -install(FILES ${gen_ruby_scripts} DESTINATION ${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/ruby/gz/${GZ_DESIGNATION}${PROJECT_VERSION_MAJOR}) - -# Install gz/msgs -gz_install_includes( - "${GZ_INCLUDE_INSTALL_DIR_POSTFIX}/gz/${GZ_DESIGNATION}" - ${gen_headers}) - -# Install gz/msgs/details -gz_install_includes( - "${GZ_INCLUDE_INSTALL_DIR_POSTFIX}/gz/${IGN_DESIGNATION}/details" - ${gen_detail_headers}) - -################################################## -# Generate gz/msgs/MessageTypes.hh -foreach (hdr ${gen_includes}) - string(CONCAT gz_msgs_headers ${gz_msgs_headers} "#include <${hdr}>\n") -endforeach() - -configure_file (${CMAKE_CURRENT_SOURCE_DIR}/MessageTypes.hh.in - ${PROJECT_BINARY_DIR}/include/gz/msgs/MessageTypes.hh) - -gz_install_includes( - "${GZ_INCLUDE_INSTALL_DIR_POSTFIX}/gz/${GZ_DESIGNATION}" - "${PROJECT_BINARY_DIR}/include/gz/${GZ_DESIGNATION}/MessageTypes.hh") - -################################################## -# Build the main library -gz_create_core_library(SOURCES - ${gen_sources} - ${PROJECT_SOURCE_DIR}/src/Factory.cc - ${PROJECT_SOURCE_DIR}/src/Filesystem.cc - ${PROJECT_SOURCE_DIR}/src/gz.cc - ${PROJECT_SOURCE_DIR}/src/Utility.cc -) - -target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} - PUBLIC - protobuf::libprotobuf - gz-math${GZ_MATH_VER}::gz-math${GZ_MATH_VER} - PRIVATE - TINYXML2::TINYXML2 -) - -if (${Protobuf_VERSION} VERSION_LESS 3.12.0) - # Older versions of protobuf (eg on focal) will throw up float-equal errors - # Fixed via: https://github.com/protocolbuffers/protobuf/pull/6000 - target_compile_options(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE -Wno-float-equal) -endif() - -target_include_directories(${PROJECT_LIBRARY_TARGET_NAME} - SYSTEM PUBLIC $) - -if (CMAKE_CXX_COMPILER_ID MATCHES "Clang") - # Disable warning in generated *.pb.cc code - target_compile_options(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE -Wno-invalid-offsetof) -endif() - -target_include_directories(${PROJECT_LIBRARY_TARGET_NAME} - PUBLIC - $ - $) - -################################################## -# Build unit tests -gz_get_libsources_and_unittests(sources gtest_sources) - -# Build the unit tests. -gz_build_tests(TYPE UNIT - SOURCES - ${gtest_sources} - LIB_DEPS - TINYXML2::TINYXML2 -) - -if (TARGET UNIT_Factory_TEST) - target_compile_definitions(UNIT_Factory_TEST - PRIVATE GZ_MSGS_TEST_PATH="${PROJECT_SOURCE_DIR}/test") -endif() - -################################################## -# gz msgs command -if(NOT WIN32) - add_subdirectory(cmd) -endif() diff --git a/src/Factory.cc b/src/Factory.cc deleted file mode 100644 index b8a10c06..00000000 --- a/src/Factory.cc +++ /dev/null @@ -1,318 +0,0 @@ -/* - * Copyright (C) 2016 Open Source Robotics Foundation - * - * 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. - * -*/ - -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable: 4146 4251) -#endif - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#ifdef _MSC_VER -#pragma warning(pop) -#endif - -#include "gz/msgs/Factory.hh" -#include "gz/msgs/Filesystem.hh" - -using namespace gz; -using namespace msgs; - -/// \def ProtobufUniquePtr -/// \brief An abbreviated unique pointer to a protobuf message type. -using ProtoUniquePtr = std::unique_ptr; - -////////////////////////////////////////////////// -/// \brief split at a one character delimiter to get a vector of something -/// \param[in] _orig The string to split -/// \param[in] _delim a character to split the string at -/// \returns vector of split pieces of the string excluding the delimiter -std::vector split(const std::string &_orig, char _delim) -{ - std::vector pieces; - size_t pos1 = 0; - size_t pos2 = _orig.find(_delim); - while (pos2 != std::string::npos) - { - pieces.push_back(_orig.substr(pos1, pos2-pos1)); - pos1 = pos2+1; - pos2 = _orig.find(_delim, pos2+1); - } - pieces.push_back(_orig.substr(pos1, _orig.size()-pos1)); - return pieces; -} - -///////////////////////////////////////////////// -/// \brief A factory class to generate protobuf messages at runtime based on -/// their message descriptors. The location of the .desc files is expected -/// via the GZ_DESCRIPTOR_PATH environment variable. This environment -/// variable expects paths to directories containing .desc files. -/// Any file without the .desc extension will be ignored. -class DynamicFactory -{ - ////////////////////////////////////////////////// - /// \brief Constructor. - /// The constructor will try to load all descriptors specified in the - /// GZ_DESCRIPTOR_PATH environment variable. - public: DynamicFactory() - { - // Try to get the list of paths from an environment variable. - const char *descPaths = std::getenv("GZ_DESCRIPTOR_PATH"); - if (!descPaths) - { - // TODO(CH3): Deprecated. Remove on tock. - // Remember to still return !! - descPaths = std::getenv("IGN_DESCRIPTOR_PATH"); - - if (!descPaths) - { - return; - } - else - { - std::cerr << "IGN_DESCRIPTOR_PATH is deprecated and will be removed! " - << "Use GZ_DESCRIPTOR_PATH instead!" << std::endl; - } - } - - // Load all the descriptors found in the paths set with GZ_DESCRIPTOR_PATH. - this->LoadDescriptors(descPaths); - } - - ////////////////////////////////////////////////// - /// \brief Load descriptors into the descriptor pool. - /// \param[in] _paths A set of directories containing .desc descriptor files. - /// Each directory should be separated by ":". - public: void LoadDescriptors(const std::string &_paths) - { - if (_paths.empty()) - return; - - // Split all the directories containing .desc files. - std::vector descDirs = split(_paths, ':'); - - for (const std::string &descDir : descDirs) - { - for (DirIter dirIter(descDir); dirIter != DirIter(); ++dirIter) - { - // Ignore files without the .desc extension. - if ((*dirIter).rfind(".desc") == std::string::npos) - continue; - - // Parse the .desc file. - std::ifstream ifs(*dirIter); - if (!ifs.is_open()) - { - std::cerr << "DynamicFactory(): Unable to open [" << *dirIter << "]" - << std::endl; - continue; - } - - google::protobuf::FileDescriptorSet fileDescriptorSet; - if (!fileDescriptorSet.ParseFromIstream(&ifs)) - { - std::cerr << "DynamicFactory(): Unable to parse descriptor set from [" - << *dirIter << "]" << std::endl; - continue; - } - - // Place the real descriptors in the descriptor pool. - for (const google::protobuf::FileDescriptorProto &fileDescriptorProto : - fileDescriptorSet.file()) - { - if (!pool.BuildFile(fileDescriptorProto)) - { - std::cerr << "DynamicFactory(). Unable to place descriptors from [" - << *dirIter << "] in the descriptor pool" << std::endl; - } - } - } - } - } - - ////////////////////////////////////////////////// - /// \brief Create a new instance of a message. - /// \param[in] _msgType Type of message to create. - /// \return Pointer to a google protobuf message. Null if the message - /// type could not be handled. - public: static ProtoUniquePtr New(const std::string &_msgType) - { - auto msgType = _msgType; - if (msgType.find("ignition") == 0) - { - msgType.replace(0, 8, "gz"); - std::cerr << "Trying to create deprecated message type [" - << _msgType << "]. Using [" << msgType << "] instead." - << std::endl; - } - - // Shortcut if the type has been already registered. - std::map>::iterator msgF = - dynamicMsgMap.find(msgType); - - if (msgF != dynamicMsgMap.end()) - return msgF->second(); - - // Nothing to do if we don't know about this type in the descriptor map. - const google::protobuf::Descriptor *descriptor = - pool.FindMessageTypeByName(msgType); - if (!descriptor) - return nullptr; - - google::protobuf::Message *msgPtr( - dynamicMessageFactory.GetPrototype(descriptor)->New()); - - // Create the lambda for registration purposes. - std::function f = [msgPtr]() -> ProtoUniquePtr - { - ProtoUniquePtr ptr(msgPtr->New()); - return ptr; - }; - - // Register the new type for the future. - dynamicMsgMap[_msgType] = f; - - return f(); - } - - /// \brief A list of registered message types built at runtime. - /// The key is the message type. The value is a function that returns a - /// std::unique_ptr to a new empty instance of the message or nullptr if - /// the message is not registered. - private: static std::map> dynamicMsgMap; - - /// \brief We store the descriptors here. - private: static google::protobuf::DescriptorPool pool; - - /// \brief Used to create a message from a descriptor. - private: static google::protobuf::DynamicMessageFactory dynamicMessageFactory; -}; - -// Initialization of static members, -std::map> -DynamicFactory::dynamicMsgMap; -google::protobuf::DescriptorPool DynamicFactory::pool; -google::protobuf::DynamicMessageFactory DynamicFactory::dynamicMessageFactory; -DynamicFactory dynamicFactory; -std::map *Factory::msgMap = NULL; - -///////////////////////////////////////////////// -void Factory::Register(const std::string &_msgType, - FactoryFn _factoryfn) -{ - // Create the msgMap if it's null - if (!msgMap) - msgMap = new std::map; - - (*msgMap)[_msgType] = _factoryfn; -} - -///////////////////////////////////////////////// -std::unique_ptr Factory::New( - const std::string &_msgType) -{ - auto msgType = _msgType; - if (msgType.find("ignition") == 0) - { - msgType.replace(0, 8, "gz"); - std::cerr << "Trying to create deprecated message type [" - << _msgType << "]. Using [" << msgType << "] instead." - << std::endl; - } - - std::unique_ptr msg; - - std::string type; - // Convert "gz.msgs." to "gz_msgs.". - if (msgType.find("gz.msgs.") == 0) - { - type = "gz_msgs." + msgType.substr(8); - } - // Convert ".gz.msgs." to "gz_msgs.". - else if (msgType.find(".gz.msgs.") == 0) - { - type = "gz_msgs." + msgType.substr(9); - } - else - { - // Fix typenames that are missing "gz_msgs." at the beginning. - if (msgType.find("gz_msgs.") != 0) - type = "gz_msgs."; - type += msgType; - } - - // Create a new message if a FactoryFn has been assigned to the message type - if (msgMap->find(type) != msgMap->end()) - return ((*msgMap)[type]) (); - - // Check if we have the message descriptor. - msg = dynamicFactory.New(msgType); - - return msg; -} - -///////////////////////////////////////////////// -std::unique_ptr Factory::New( - const std::string &_msgType, const std::string &_args) -{ - auto msgType = _msgType; - if (msgType.find("ignition") == 0) - { - msgType.replace(0, 8, "gz"); - std::cerr << "Trying to create deprecated message type [" - << _msgType << "]. Using [" << msgType << "] instead." - << std::endl; - } - - std::unique_ptr msg = New(msgType); - if (msg) - { - google::protobuf::TextFormat::ParseFromString(_args, msg.get()); - } - - return msg; -} - -///////////////////////////////////////////////// -void Factory::Types(std::vector &_types) -{ - _types.clear(); - - // Return the list of all known message types. - std::map::const_iterator iter; - for (iter = msgMap->begin(); iter != msgMap->end(); ++iter) - { - _types.push_back(iter->first); - } -} - -///////////////////////////////////////////////// -void Factory::LoadDescriptors(const std::string &_paths) -{ - dynamicFactory.LoadDescriptors(_paths); -} diff --git a/src/Filesystem.cc b/src/Filesystem.cc deleted file mode 100644 index 05976cad..00000000 --- a/src/Filesystem.cc +++ /dev/null @@ -1,272 +0,0 @@ -/* - * Copyright 2002-2009, 2014 Beman Dawes - * Copyright 2001 Dietmar Kuehl - * - * Distributed under the Boost Software License, Version 1.0. - * - * Boost Software License - Version 1.0 - August 17th, 2003 - * - * Permission is hereby granted, free of charge, to any person or organization - * obtaining a copy of the software and accompanying documentation covered by - * this license (the "Software") to use, reproduce, display, distribute, - * execute, and transmit the Software, and to prepare derivative works of the - * Software, and to permit third-parties to whom the Software is furnished to - * do so, all subject to the following: - * - * The copyright notices in the Software and this entire statement, including - * the above license grant, this restriction and the following disclaimer, - * must be included in all copies of the Software, in whole or in part, and - * all derivative works of the Software, unless such copies or derivative - * works are solely in the form of machine-executable object code generated by - * a source language processor. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT - * SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE - * FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE, - * ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER - * DEALINGS IN THE SOFTWARE. - */ - -/* - * Most of this code was borrowed from Boost in - * libs/filesystem/src/operations.cpp and - * libs/filesystem/include/boost/filesystem/operations.hpp. - */ - -#ifndef _WIN32 -#include -#include -#include -#include -#include -#include -#include -#include -#else -#include -#include -#include -#endif - -#include -#include -#include -#include -#include - -#include "gz/msgs/Filesystem.hh" - -namespace gz -{ - namespace msgs - { - /// \internal - /// \brief Private data for the DirIter class. - class DirIterPrivate - { - /// \def current - /// \brief The current directory item. - public: std::string current; - - /// \def dirname - /// \brief The original path to the directory. - public: std::string dirname; - - /// \def handle - /// \brief Opaque handle for holding the directory iterator. - public: void *handle; - - /// \def end - /// \brief Private variable to indicate whether the iterator has reached - /// the end. - public: bool end; - }; - -#ifndef _WIN32 - - static const char preferred_separator = '/'; - - ////////////////////////////////////////////////// - DirIter::DirIter(const std::string &_in) : dataPtr(new DirIterPrivate) - { - this->dataPtr->dirname = _in; - - this->dataPtr->current = ""; - - this->dataPtr->handle = opendir(_in.c_str()); - - this->dataPtr->end = false; - - if (this->dataPtr->handle == nullptr) - { - this->dataPtr->end = true; - } - else - { - Next(); - } - } - - ////////////////////////////////////////////////// - void DirIter::Next() - { - while (true) - { - struct dirent *entry = - readdir(reinterpret_cast(this->dataPtr->handle)); // NOLINT - if (!entry) - { - this->dataPtr->end = true; - this->dataPtr->current = ""; - break; - } - - if ((strcmp(entry->d_name, ".") != 0) - && (strcmp(entry->d_name, "..") != 0)) - { - this->dataPtr->current = std::string(entry->d_name); - break; - } - } - } - - ////////////////////////////////////////////////// - void DirIter::CloseHandle() - { - closedir(reinterpret_cast(this->dataPtr->handle)); - } - -#else // Windows - - static const char preferred_separator = '\\'; - - ////////////////////////////////////////////////// - static bool not_found_error(int _errval) - { - return _errval == ERROR_FILE_NOT_FOUND - || _errval == ERROR_PATH_NOT_FOUND - || _errval == ERROR_INVALID_NAME // "tools/src/:sys:stat.h", "//foo" - || _errval == ERROR_INVALID_DRIVE // USB card reader with no card - || _errval == ERROR_NOT_READY // CD/DVD drive with no disc inserted - || _errval == ERROR_INVALID_PARAMETER // ":sys:stat.h" - || _errval == ERROR_BAD_PATHNAME // "//nosuch" on Win64 - || _errval == ERROR_BAD_NETPATH; // "//nosuch" on Win32 - } - -#ifndef MAXIMUM_REPARSE_DATA_BUFFER_SIZE -#define MAXIMUM_REPARSE_DATA_BUFFER_SIZE (16 * 1024) -#endif - - ////////////////////////////////////////////////// - DirIter::DirIter(const std::string &_in) : dataPtr(new DirIterPrivate) - { - // use a form of search Sebastian Martel reports will work with Win98 - this->dataPtr->dirname = _in; - - this->dataPtr->current = ""; - - this->dataPtr->end = false; - - if (_in.empty()) - { - // To be compatible with Unix, if given an empty string, assume this - // is the end. - this->dataPtr->end = true; - return; - } - - std::string dirpath(_in); - dirpath += (dirpath.empty() - || (dirpath[dirpath.size()-1] != '\\' - && dirpath[dirpath.size()-1] != '/' - && dirpath[dirpath.size()-1] != ':'))? "\\*" : "*"; - - WIN32_FIND_DATAA data; - if ((this->dataPtr->handle = ::FindFirstFileA(dirpath.c_str(), &data)) - == INVALID_HANDLE_VALUE) - { - this->dataPtr->handle = nullptr; // signal eof - this->dataPtr->end = true; - } - else - { - this->dataPtr->current = std::string(data.cFileName); - } - } - - ////////////////////////////////////////////////// - void DirIter::Next() - { - WIN32_FIND_DATAA data; - if (::FindNextFileA(this->dataPtr->handle, &data) == 0) // fails - { - this->dataPtr->end = true; - this->dataPtr->current = ""; - } - else - { - this->dataPtr->current = std::string(data.cFileName); - } - } - - ////////////////////////////////////////////////// - void DirIter::CloseHandle() - { - ::FindClose(this->dataPtr->handle); - } - -#endif // _WIN32 - - ////////////////////////////////////////////////// - std::string separator(const std::string &_p) - { - return _p + preferred_separator; - } - - ////////////////////////////////////////////////// - DirIter::DirIter() : dataPtr(new DirIterPrivate) - { - this->dataPtr->current = ""; - - this->dataPtr->dirname = ""; - - this->dataPtr->handle = nullptr; - - this->dataPtr->end = true; - } - - ////////////////////////////////////////////////// - std::string DirIter::operator*() const - { - return this->dataPtr->dirname + preferred_separator + - this->dataPtr->current; - } - - ////////////////////////////////////////////////// - // prefix operator; note that we don't support the postfix operator - // because it is complicated to do so - const DirIter& DirIter::operator++() - { - Next(); - return *this; - } - - ////////////////////////////////////////////////// - bool DirIter::operator!=(const DirIter &_other) const - { - return this->dataPtr->end != _other.dataPtr->end; - } - - ////////////////////////////////////////////////// - DirIter::~DirIter() - { - if (this->dataPtr->handle != nullptr) - { - CloseHandle(); - this->dataPtr->handle = nullptr; - } - } - } -} diff --git a/src/Utility.cc b/src/Utility.cc deleted file mode 100644 index 400cc6fa..00000000 --- a/src/Utility.cc +++ /dev/null @@ -1,1358 +0,0 @@ -/* - * Copyright (C) 2016 Open Source Robotics Foundation - * - * 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 -#include -#include "gz/msgs/Utility.hh" - -namespace gz -{ - namespace msgs - { - // Inline bracket to help doxygen filtering. - inline namespace GZ_MSGS_VERSION_NAMESPACE { - /// \brief Left and right trim a string. This was copied from Gazebo - /// common, gz-common/Util.hh, to avoid adding another dependency. - /// Remove this function if gz-common ever becomes a dependency. - /// \param[in] _s String to trim - /// \return Trimmed string - std::string trimmed(std::string _s) - { - // Left trim - _s.erase(_s.begin(), std::find_if(_s.begin(), _s.end(), - [](int c) {return !std::isspace(c);})); - - // Right trim - _s.erase(std::find_if(_s.rbegin(), _s.rend(), - [](int c) {return !std::isspace(c);}).base(), _s.end()); - - return _s; - } - - ///////////////////////////////////////////// - gz::math::Vector3d Convert(const msgs::Vector3d &_v) - { - return gz::math::Vector3d(_v.x(), _v.y(), _v.z()); - } - - ///////////////////////////////////////////// - gz::math::Vector2d Convert(const msgs::Vector2d &_v) - { - return gz::math::Vector2d(_v.x(), _v.y()); - } - - ///////////////////////////////////////////// - gz::math::Quaterniond Convert(const msgs::Quaternion &_q) - { - return gz::math::Quaterniond(_q.w(), _q.x(), _q.y(), _q.z()); - } - - ///////////////////////////////////////////// - gz::math::Pose3d Convert(const msgs::Pose &_p) - { - gz::math::Pose3d result; - - if (_p.has_position()) - result.Pos() = Convert(_p.position()); - if (_p.has_orientation()) - result.Rot() = Convert(_p.orientation()); - - return result; - } - - ///////////////////////////////////////////// - math::Inertiald Convert(const msgs::Inertial &_i) - { - auto pose = msgs::Convert(_i.pose()); - - if (_i.fluid_added_mass().empty()) - { - return math::Inertiald( - math::MassMatrix3d( - _i.mass(), - math::Vector3d(_i.ixx(), _i.iyy(), _i.izz()), - math::Vector3d(_i.ixy(), _i.ixz(), _i.iyz())), - pose); - } - - math::Matrix6d addedMass{ - _i.fluid_added_mass(0), - _i.fluid_added_mass(1), - _i.fluid_added_mass(2), - _i.fluid_added_mass(3), - _i.fluid_added_mass(4), - _i.fluid_added_mass(5), - - _i.fluid_added_mass(1), - _i.fluid_added_mass(6), - _i.fluid_added_mass(7), - _i.fluid_added_mass(8), - _i.fluid_added_mass(9), - _i.fluid_added_mass(10), - - _i.fluid_added_mass(2), - _i.fluid_added_mass(7), - _i.fluid_added_mass(11), - _i.fluid_added_mass(12), - _i.fluid_added_mass(13), - _i.fluid_added_mass(14), - - _i.fluid_added_mass(3), - _i.fluid_added_mass(8), - _i.fluid_added_mass(12), - _i.fluid_added_mass(15), - _i.fluid_added_mass(16), - _i.fluid_added_mass(17), - - _i.fluid_added_mass(4), - _i.fluid_added_mass(9), - _i.fluid_added_mass(13), - _i.fluid_added_mass(16), - _i.fluid_added_mass(18), - _i.fluid_added_mass(19), - - _i.fluid_added_mass(5), - _i.fluid_added_mass(10), - _i.fluid_added_mass(14), - _i.fluid_added_mass(17), - _i.fluid_added_mass(19), - _i.fluid_added_mass(20) - }; - - return math::Inertiald( - math::MassMatrix3d( - _i.mass(), - math::Vector3d(_i.ixx(), _i.iyy(), _i.izz()), - math::Vector3d(_i.ixy(), _i.ixz(), _i.iyz())), - pose, addedMass); - } - - ///////////////////////////////////////////// - math::SphericalCoordinates Convert(const msgs::SphericalCoordinates &_sc) - { - math::SphericalCoordinates out; - if (_sc.surface_model() == msgs::SphericalCoordinates::EARTH_WGS84) - { - out.SetSurface(math::SphericalCoordinates::EARTH_WGS84); - } - else if (_sc.surface_model() == msgs::SphericalCoordinates::MOON_SCS) - { - out.SetSurface(math::SphericalCoordinates::MOON_SCS); - } - else if (_sc.surface_model() == - msgs::SphericalCoordinates::CUSTOM_SURFACE) - { - out.SetSurface(math::SphericalCoordinates::CUSTOM_SURFACE, - _sc.surface_axis_equatorial(), _sc.surface_axis_polar()); - } - else - { - std::cerr << "Unrecognized spherical surface type [" - << _sc.surface_model() - << "]. Using default." << std::endl; - } - out.SetLatitudeReference(GZ_DTOR(_sc.latitude_deg())); - out.SetLongitudeReference(GZ_DTOR(_sc.longitude_deg())); - out.SetElevationReference(_sc.elevation()); - out.SetHeadingOffset(GZ_DTOR(_sc.heading_deg())); - return out; - } - - ///////////////////////////////////////////// - math::AxisAlignedBox Convert(const msgs::AxisAlignedBox &_b) - { - return math::AxisAlignedBox(msgs::Convert(_b.min_corner()), - msgs::Convert(_b.max_corner())); - } - - ///////////////////////////////////////////// - msgs::AxisAlignedBox Convert(const math::AxisAlignedBox &_b) - { - msgs::AxisAlignedBox result; - msgs::Set(result.mutable_min_corner(), _b.Min()); - msgs::Set(result.mutable_max_corner(), _b.Max()); - return result; - } - - ///////////////////////////////////////////// - void Set(msgs::AxisAlignedBox *_b, const math::AxisAlignedBox &_v) - { - msgs::Set(_b->mutable_min_corner(), _v.Min()); - msgs::Set(_b->mutable_max_corner(), _v.Max()); - } - - ///////////////////////////////////////////// - math::Color Convert(const msgs::Color &_c) - { - return math::Color(_c.r(), _c.g(), _c.b(), _c.a()); - } - - ///////////////////////////////////////////// - gz::math::Planed Convert(const msgs::PlaneGeom &_p) - { - return gz::math::Planed(Convert(_p.normal()), - gz::math::Vector2d(_p.size().x(), _p.size().y()), - _p.d()); - } - - ///////////////////////////////////////////// - std::string Convert(const msgs::StringMsg &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////// - bool Convert(const msgs::Boolean &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////// - int32_t Convert(const msgs::Int32 &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////// - uint32_t Convert(const msgs::UInt32 &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////// - int64_t Convert(const msgs::Int64 &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////// - uint64_t Convert(const msgs::UInt64 &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////// - double Convert(const msgs::Double &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////// - float Convert(const msgs::Float &_m) - { - return _m.data(); - } - - ///////////////////////////////////////////////// - std::chrono::steady_clock::duration Convert(const msgs::Time &_time) - { - return std::chrono::seconds(_time.sec()) + - std::chrono::nanoseconds(_time.nsec()); - } - - ///////////////////////////////////////////////// - msgs::Vector3d Convert(const gz::math::Vector3d &_v) - { - msgs::Vector3d result; - result.set_x(_v.X()); - result.set_y(_v.Y()); - result.set_z(_v.Z()); - return result; - } - - ///////////////////////////////////////////////// - msgs::Vector2d Convert(const gz::math::Vector2d &_v) - { - msgs::Vector2d result; - result.set_x(_v.X()); - result.set_y(_v.Y()); - return result; - } - - ///////////////////////////////////////////// - msgs::Quaternion Convert(const gz::math::Quaterniond &_q) - { - msgs::Quaternion result; - result.set_x(_q.X()); - result.set_y(_q.Y()); - result.set_z(_q.Z()); - result.set_w(_q.W()); - return result; - } - - ///////////////////////////////////////////// - msgs::Pose Convert(const gz::math::Pose3d &_p) - { - msgs::Pose result; - result.mutable_position()->CopyFrom(Convert(_p.Pos())); - result.mutable_orientation()->CopyFrom(Convert(_p.Rot())); - return result; - } - - ///////////////////////////////////////////// - msgs::Color Convert(const math::Color &_c) - { - msgs::Color result; - result.set_r(_c.R()); - result.set_g(_c.G()); - result.set_b(_c.B()); - result.set_a(_c.A()); - return result; - } - - ///////////////////////////////////////////// - msgs::Inertial Convert(const math::Inertiald &_i) - { - msgs::Inertial result; - msgs::Set(&result, _i); - return result; - } - - ///////////////////////////////////////////// - msgs::Inertial Convert(const math::MassMatrix3d &_m) - { - msgs::Inertial result; - msgs::Set(&result, _m); - return result; - } - - ///////////////////////////////////////////// - msgs::SphericalCoordinates Convert(const math::SphericalCoordinates &_sc) - { - msgs::SphericalCoordinates result; - msgs::Set(&result, _sc); - return result; - } - - ///////////////////////////////////////////// - msgs::PlaneGeom Convert(const gz::math::Planed &_p) - { - msgs::PlaneGeom result; - result.mutable_normal()->CopyFrom(Convert(_p.Normal())); - result.mutable_size()->set_x(_p.Size().X()); - result.mutable_size()->set_y(_p.Size().Y()); - result.set_d(_p.Offset()); - return result; - } - - ///////////////////////////////////////////// - msgs::StringMsg Convert(const std::string &_s) - { - msgs::StringMsg result; - result.set_data(_s); - return result; - } - - ///////////////////////////////////////////// - msgs::Boolean Convert(const bool &_b) - { - msgs::Boolean result; - result.set_data(_b); - return result; - } - - ///////////////////////////////////////////// - msgs::Int32 Convert(const int32_t &_i) - { - msgs::Int32 result; - result.set_data(_i); - return result; - } - - ///////////////////////////////////////////// - msgs::UInt32 Convert(const uint32_t &_u) - { - msgs::UInt32 result; - result.set_data(_u); - return result; - } - - ///////////////////////////////////////////// - msgs::Int64 Convert(const int64_t &_i) - { - msgs::Int64 result; - result.set_data(_i); - return result; - } - - ///////////////////////////////////////////// - msgs::UInt64 Convert(const uint64_t &_u) - { - msgs::UInt64 result; - result.set_data(_u); - return result; - } - - - ///////////////////////////////////////////// - msgs::Double Convert(const double &_d) - { - msgs::Double result; - result.set_data(_d); - return result; - } - - ///////////////////////////////////////////////// - msgs::Time Convert(const std::chrono::steady_clock::duration &_time_point) - { - std::pair timeSecAndNsecs = - gz::math::durationToSecNsec(_time_point); - msgs::Time msg; - msg.set_sec(timeSecAndNsecs.first); - msg.set_nsec(timeSecAndNsecs.second); - return msg; - } - - ///////////////////////////////////////////// - msgs::Float Convert(const float &_f) - { - msgs::Float result; - result.set_data(_f); - return result; - } - - ///////////////////////////////////////////// - void Set(msgs::Vector3d *_pt, const gz::math::Vector3d &_v) - { - _pt->set_x(_v.X()); - _pt->set_y(_v.Y()); - _pt->set_z(_v.Z()); - } - - ///////////////////////////////////////////// - void Set(msgs::Vector2d *_pt, const gz::math::Vector2d &_v) - { - _pt->set_x(_v.X()); - _pt->set_y(_v.Y()); - } - - ///////////////////////////////////////////// - void Set(msgs::Quaternion *_q, const gz::math::Quaterniond &_v) - { - _q->set_x(_v.X()); - _q->set_y(_v.Y()); - _q->set_z(_v.Z()); - _q->set_w(_v.W()); - } - - ///////////////////////////////////////////// - void Set(msgs::Pose *_p, const gz::math::Pose3d &_v) - { - Set(_p->mutable_position(), _v.Pos()); - Set(_p->mutable_orientation(), _v.Rot()); - } - - ///////////////////////////////////////////////// - void Set(msgs::PlaneGeom *_p, const gz::math::Planed &_v) - { - Set(_p->mutable_normal(), _v.Normal()); - _p->mutable_size()->set_x(_v.Size().X()); - _p->mutable_size()->set_y(_v.Size().Y()); - _p->set_d(_v.Offset()); - } - - ///////////////////////////////////////////// - void Set(msgs::Color *_c, const math::Color &_v) - { - _c->set_r(_v.R()); - _c->set_g(_v.G()); - _c->set_b(_v.B()); - _c->set_a(_v.A()); - } - - ///////////////////////////////////////////////// - void Set(msgs::Inertial *_i, const math::MassMatrix3d &_m) - { - _i->set_mass(_m.Mass()); - _i->set_ixx(_m.Ixx()); - _i->set_iyy(_m.Iyy()); - _i->set_izz(_m.Izz()); - _i->set_ixy(_m.Ixy()); - _i->set_ixz(_m.Ixz()); - _i->set_iyz(_m.Iyz()); - } - - ///////////////////////////////////////////////// - void Set(msgs::Inertial *_i, const math::Inertiald &_m) - { - msgs::Set(_i, _m.MassMatrix()); - msgs::Set(_i->mutable_pose(), _m.Pose()); - - if (_m.FluidAddedMass().has_value()) - { - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(0, 0)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(0, 1)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(0, 2)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(0, 3)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(0, 4)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(0, 5)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(1, 1)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(1, 2)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(1, 3)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(1, 4)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(1, 5)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(2, 2)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(2, 3)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(2, 4)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(2, 5)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(3, 3)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(3, 4)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(3, 5)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(4, 4)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(4, 5)); - _i->add_fluid_added_mass(_m.FluidAddedMass().value()(5, 5)); - } - } - - ///////////////////////////////////////////////// - void Set(msgs::SphericalCoordinates *_sc, - const math::SphericalCoordinates &_m) - { - if (_m.Surface() == math::SphericalCoordinates::EARTH_WGS84) - { - _sc->set_surface_model(msgs::SphericalCoordinates::EARTH_WGS84); - } - else if (_m.Surface() == math::SphericalCoordinates::MOON_SCS) - { - _sc->set_surface_model(msgs::SphericalCoordinates::MOON_SCS); - } - else if (_m.Surface() == - math::SphericalCoordinates::CUSTOM_SURFACE) - { - _sc->set_surface_model( - msgs::SphericalCoordinates::CUSTOM_SURFACE); - _sc->set_surface_axis_equatorial(_m.SurfaceAxisEquatorial()); - _sc->set_surface_axis_polar(_m.SurfaceAxisPolar()); - } - else - { - std::cerr << "Unrecognized spherical surface type [" - << _m.Surface() - << "]. Not populating message field." << std::endl; - } - _sc->set_latitude_deg(_m.LatitudeReference().Degree()); - _sc->set_longitude_deg(_m.LongitudeReference().Degree()); - _sc->set_elevation(_m.ElevationReference()); - _sc->set_heading_deg(_m.HeadingOffset().Degree()); - } - - ///////////////////////////////////////////////// - void Set(msgs::StringMsg *_p, const std::string &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////////// - void Set(msgs::Boolean *_p, const bool &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////////// - void Set(msgs::Int32 *_p, const int32_t &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////////// - void Set(msgs::UInt32 *_p, const uint32_t &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////////// - void Set(msgs::Int64 *_p, const int64_t &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////////// - void Set(msgs::UInt64 *_p, const uint64_t &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////////// - void Set(msgs::Double *_p, const double &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////////// - void Set(msgs::Float *_p, const float &_v) - { - _p->set_data(_v); - } - - ///////////////////////////////////////////// - msgs::Joint::Type ConvertJointType(const std::string &_str) - { - msgs::Joint::Type result = msgs::Joint::REVOLUTE; - if (_str == "revolute") - { - result = msgs::Joint::REVOLUTE; - } - else if (_str == "revolute2") - { - result = msgs::Joint::REVOLUTE2; - } - else if (_str == "prismatic") - { - result = msgs::Joint::PRISMATIC; - } - else if (_str == "universal") - { - result = msgs::Joint::UNIVERSAL; - } - else if (_str == "ball") - { - result = msgs::Joint::BALL; - } - else if (_str == "screw") - { - result = msgs::Joint::SCREW; - } - else if (_str == "gearbox") - { - result = msgs::Joint::GEARBOX; - } - else if (_str == "fixed") - { - result = msgs::Joint::FIXED; - } - else if (_str == "continuous") - { - result = msgs::Joint::CONTINUOUS; - } - else - { - std::cerr << "Unrecognized JointType [" - << _str - << "], returning msgs::Joint::REVOLUTE" - << std::endl; - } - return result; - } - - ///////////////////////////////////////////// - std::string ConvertJointType(const msgs::Joint::Type &_type) - { - std::string result; - switch (_type) - { - case msgs::Joint::REVOLUTE: - { - result = "revolute"; - break; - } - case msgs::Joint::REVOLUTE2: - { - result = "revolute2"; - break; - } - case msgs::Joint::PRISMATIC: - { - result = "prismatic"; - break; - } - case msgs::Joint::UNIVERSAL: - { - result = "universal"; - break; - } - case msgs::Joint::BALL: - { - result = "ball"; - break; - } - case msgs::Joint::SCREW: - { - result = "screw"; - break; - } - case msgs::Joint::GEARBOX: - { - result = "gearbox"; - break; - } - case msgs::Joint::FIXED: - { - result = "fixed"; - break; - } - case msgs::Joint::CONTINUOUS: - { - result = "continuous"; - break; - } - default: - { - result = "unknown"; - std::cerr << "Unrecognized JointType [" - << _type - << "], returning 'unknown'" - << std::endl; - break; - } - } - return result; - } - - ///////////////////////////////////////////////// - msgs::Geometry::Type ConvertGeometryType(const std::string &_str) - { - msgs::Geometry::Type result = msgs::Geometry::BOX; - if (_str == "box") - { - result = msgs::Geometry::BOX; - } - else if (_str == "capsule") - { - result = msgs::Geometry::CAPSULE; - } - else if (_str == "cylinder") - { - result = msgs::Geometry::CYLINDER; - } - else if (_str == "ellipsoid") - { - result = msgs::Geometry::ELLIPSOID; - } - else if (_str == "sphere") - { - result = msgs::Geometry::SPHERE; - } - else if (_str == "plane") - { - result = msgs::Geometry::PLANE; - } - else if (_str == "image") - { - result = msgs::Geometry::IMAGE; - } - else if (_str == "heightmap") - { - result = msgs::Geometry::HEIGHTMAP; - } - else if (_str == "mesh") - { - result = msgs::Geometry::MESH; - } - else if (_str == "polyline") - { - result = msgs::Geometry::POLYLINE; - } - else - { - std::cerr << "Unrecognized Geometry::Type [" - << _str - << "], returning msgs::Geometry::BOX" - << std::endl; - } - - return result; - } - - ///////////////////////////////////////////////// - std::string ConvertGeometryType(const msgs::Geometry::Type _type) - { - std::string result; - switch (_type) - { - case msgs::Geometry::BOX: - { - result = "box"; - break; - } - case msgs::Geometry::CAPSULE: - { - result = "capsule"; - break; - } - case msgs::Geometry::CYLINDER: - { - result = "cylinder"; - break; - } - case msgs::Geometry::ELLIPSOID: - { - result = "ellipsoid"; - break; - } - case msgs::Geometry::SPHERE: - { - result = "sphere"; - break; - } - case msgs::Geometry::PLANE: - { - result = "plane"; - break; - } - case msgs::Geometry::IMAGE: - { - result = "image"; - break; - } - case msgs::Geometry::HEIGHTMAP: - { - result = "heightmap"; - break; - } - case msgs::Geometry::MESH: - { - result = "mesh"; - break; - } - case msgs::Geometry::POLYLINE: - { - result = "polyline"; - break; - } - default: - { - result = "unknown"; - std::cerr << "Unrecognized Geometry::Type [" - << _type - << "], returning 'unknown'" - << std::endl; - break; - } - } - return result; - } - - ///////////////////////////////////////////////// - msgs::Material::ShaderType ConvertShaderType(const std::string &_str) - { - auto result = msgs::Material::VERTEX; - if (_str == "vertex") - { - result = msgs::Material::VERTEX; - } - else if (_str == "pixel") - { - result = msgs::Material::PIXEL; - } - else if (_str == "normal_map_object_space") - { - result = msgs::Material::NORMAL_MAP_OBJECT_SPACE; - } - else if (_str == "normal_map_tangent_space") - { - result = msgs::Material::NORMAL_MAP_TANGENT_SPACE; - } - else - { - std::cerr << "Unrecognized Material::ShaderType [" - << _str - << "], returning msgs::Material::VERTEX" - << std::endl; - } - return result; - } - - ///////////////////////////////////////////////// - std::string ConvertShaderType(const msgs::Material::ShaderType &_type) - { - std::string result; - switch (_type) - { - case msgs::Material::VERTEX: - { - result = "vertex"; - break; - } - case msgs::Material::PIXEL: - { - result = "pixel"; - break; - } - case msgs::Material::NORMAL_MAP_OBJECT_SPACE: - { - result = "normal_map_object_space"; - break; - } - case msgs::Material::NORMAL_MAP_TANGENT_SPACE: - { - result = "normal_map_tangent_space"; - break; - } - default: - { - result = "unknown"; - std::cerr << "Unrecognized Material::ShaderType [" - << _type - << "], returning 'unknown'" - << std::endl; - break; - } - } - return result; - } - - ///////////////////////////////////////////////// - void InitPointCloudPacked(msgs::PointCloudPacked &_msg, - const std::string &_frameId, bool _memoryAligned, - const std::vector> &_fields) - { - uint32_t offset = 0; - - // Helper function that will set a single field. - std::function initPointCloudPackedHelper = - [&](const std::string &_name, - msgs::PointCloudPacked::Field::DataType _type) -> void - { - msgs::PointCloudPacked::Field *newField = _msg.add_field(); - newField->set_name(_name); - newField->set_count(1); - newField->set_datatype(_type); - newField->set_offset(offset); - switch (_type) - { - case msgs::PointCloudPacked::Field::INT8: - case msgs::PointCloudPacked::Field::UINT8: - offset += 1; - break; - case msgs::PointCloudPacked::Field::INT16: - case msgs::PointCloudPacked::Field::UINT16: - offset += 2; - break; - case msgs::PointCloudPacked::Field::INT32: - case msgs::PointCloudPacked::Field::UINT32: - case msgs::PointCloudPacked::Field::FLOAT32: - offset += 4; - break; - case msgs::PointCloudPacked::Field::FLOAT64: - offset += 8; - break; - // LCOV_EXCL_START - default: - std::cerr << "PointCloudPacked field datatype of [" - << _type << "] is invalid.\n"; - break; - // LCOV_EXCL_STOP - } - }; - - // Set the frame - _msg.mutable_header()->clear_data(); - msgs::Header::Map *frame = _msg.mutable_header()->add_data(); - frame->set_key("frame_id"); - frame->add_value(_frameId); - - _msg.clear_field(); - // Setup the point cloud message. - for (const std::pair &field : _fields) - { - if (field.first == "xyz") - { - initPointCloudPackedHelper("x", field.second); - initPointCloudPackedHelper("y", field.second); - initPointCloudPackedHelper("z", field.second); - } - else - { - initPointCloudPackedHelper(field.first, field.second); - } - - // Memory align the field. - if (_memoryAligned) - offset = math::roundUpMultiple(offset, sizeof(size_t)); - } - - // Set the point_step - if (_memoryAligned) - _msg.set_point_step(math::roundUpMultiple(offset, sizeof(size_t))); - else - _msg.set_point_step(offset); - } - - ///////////////////////////////////////////// - std::string ToString(const msgs::Discovery::Type &_t) - { - switch (_t) - { - default: - case msgs::Discovery::UNINITIALIZED: - return "UNINITIALIZED"; - case msgs::Discovery::ADVERTISE: - return "ADVERTISE"; - case msgs::Discovery::SUBSCRIBE: - return "SUBSCRIBE"; - case msgs::Discovery::UNADVERTISE: - return "UNADVERTISE"; - case msgs::Discovery::HEARTBEAT: - return "HEARTBEAT"; - case msgs::Discovery::BYE: - return "BYE"; - case msgs::Discovery::NEW_CONNECTION: - return "NEW_CONNECTION"; - case msgs::Discovery::END_CONNECTION: - return "END_CONNECTION"; - case msgs::Discovery::SUBSCRIBERS_REQ: - return "SUBSCRIBERS_REQ"; - case msgs::Discovery::SUBSCRIBERS_REP: - return "SUBSCRIBERS_REP"; - }; - } - - ///////////////////////////////////////////// - msgs::PixelFormatType ConvertPixelFormatType(const std::string &_str) - { - if (_str == "L_INT8") - { - return msgs::PixelFormatType::L_INT8; - } - else if (_str == "L_INT16") - { - return msgs::PixelFormatType::L_INT16; - } - else if (_str == "RGB_INT8") - { - return msgs::PixelFormatType::RGB_INT8; - } - else if (_str == "RGBA_INT8") - { - return msgs::PixelFormatType::RGBA_INT8; - } - else if (_str == "BGRA_INT8") - { - return msgs::PixelFormatType::BGRA_INT8; - } - else if (_str == "RGB_INT16") - { - return msgs::PixelFormatType::RGB_INT16; - } - else if (_str == "RGB_INT32") - { - return msgs::PixelFormatType::RGB_INT32; - } - else if (_str == "BGR_INT8") - { - return msgs::PixelFormatType::BGR_INT8; - } - else if (_str == "BGR_INT16") - { - return msgs::PixelFormatType::BGR_INT16; - } - else if (_str == "BGR_INT32") - { - return msgs::PixelFormatType::BGR_INT32; - } - else if (_str == "R_FLOAT16") - { - return msgs::PixelFormatType::R_FLOAT16; - } - else if (_str == "RGB_FLOAT16") - { - return msgs::PixelFormatType::RGB_FLOAT16; - } - else if (_str == "R_FLOAT32") - { - return msgs::PixelFormatType::R_FLOAT32; - } - else if (_str == "RGB_FLOAT32") - { - return msgs::PixelFormatType::RGB_FLOAT32; - } - else if (_str == "BAYER_RGGB8") - { - return msgs::PixelFormatType::BAYER_RGGB8; - } - else if (_str == "BAYER_BGGR8") - { - return msgs::PixelFormatType::BAYER_BGGR8; - } - else if (_str == "BAYER_GBRG8") - { - return msgs::PixelFormatType::BAYER_GBRG8; - } - else if (_str == "BAYER_GRBG8") - { - return msgs::PixelFormatType::BAYER_GRBG8; - } - - return msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT; - } - - ///////////////////////////////////////////// - std::string ConvertPixelFormatType(const msgs::PixelFormatType &_t) - { - switch (_t) - { - default: - case msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT: - return "UNKNOWN_PIXEL_FORMAT"; - case msgs::PixelFormatType::L_INT8: - return "L_INT8"; - case msgs::PixelFormatType::L_INT16: - return "L_INT16"; - case msgs::PixelFormatType::RGB_INT8: - return "RGB_INT8"; - case msgs::PixelFormatType::RGBA_INT8: - return "RGBA_INT8"; - case msgs::PixelFormatType::BGRA_INT8: - return "BGRA_INT8"; - case msgs::PixelFormatType::RGB_INT16: - return "RGB_INT16"; - case msgs::PixelFormatType::RGB_INT32: - return "RGB_INT32"; - case msgs::PixelFormatType::BGR_INT8: - return "BGR_INT8"; - case msgs::PixelFormatType::BGR_INT16: - return "BGR_INT16"; - case msgs::PixelFormatType::BGR_INT32: - return "BGR_INT32"; - case msgs::PixelFormatType::R_FLOAT16: - return "R_FLOAT16"; - case msgs::PixelFormatType::RGB_FLOAT16: - return "RGB_FLOAT16"; - case msgs::PixelFormatType::R_FLOAT32: - return "R_FLOAT32"; - case msgs::PixelFormatType::RGB_FLOAT32: - return "RGB_FLOAT32"; - case msgs::PixelFormatType::BAYER_RGGB8: - return "BAYER_RGGB8"; - case msgs::PixelFormatType::BAYER_BGGR8: - return "BAYER_BGGR8"; - case msgs::PixelFormatType::BAYER_GBRG8: - return "BAYER_GBRG8"; - case msgs::PixelFormatType::BAYER_GRBG8: - return "BAYER_GRBG8"; - }; - } - - ///////////////////////////////////////////////// - bool ConvertFuelMetadata(const std::string &_modelConfigStr, - msgs::FuelMetadata &_meta) - { - gz::msgs::FuelMetadata meta; - - // Load the model config into tinyxml - tinyxml2::XMLDocument modelConfigDoc; - if (modelConfigDoc.Parse(_modelConfigStr.c_str()) != - tinyxml2::XML_SUCCESS) - { - std::cerr << "Unable to parse model config XML string.\n"; - return false; - } - - // Get the top level or element. - tinyxml2::XMLElement *topElement = modelConfigDoc.FirstChildElement( - "model"); - bool isModel = true; - if (!topElement) - { - topElement = modelConfigDoc.FirstChildElement("world"); - if (!topElement) - { - std::cerr << "Model config string does not contain a " - << " or element\n"; - return false; - } - isModel = false; - } - - // Read the name, which is a mandatory element. - tinyxml2::XMLElement *elem = topElement->FirstChildElement("name"); - if (!elem || !elem->GetText()) - { - std::cerr << "Model config string does not contain a element\n"; - return false; - } - meta.set_name(trimmed(elem->GetText())); - - // Read the version, if present. - elem = topElement->FirstChildElement("version"); - if (elem && elem->GetText()) - { - auto version = std::stoi(trimmed(elem->GetText())); - meta.set_version(version); - } - - // Read the description, if present. - elem = topElement->FirstChildElement("description"); - if (elem && elem->GetText()) - meta.set_description(trimmed(elem->GetText())); - - // Read the dependencies, if any. - elem = topElement->FirstChildElement("depend"); - while (elem) - { - auto modelElem = elem->FirstChildElement("model"); - if (modelElem) - { - auto uriElem = modelElem->FirstChildElement("uri"); - if (uriElem) - { - auto dependency = meta.add_dependencies(); - dependency->set_uri(uriElem->GetText()); - } - } - elem = elem->NextSiblingElement("depend"); - } - - // Read the authors, if any. - elem = topElement->FirstChildElement("author"); - while (elem) - { - gz::msgs::FuelMetadata::Contact *author = meta.add_authors(); - // Get the author name and email - if (elem->FirstChildElement("name") && - elem->FirstChildElement("name")->GetText()) - { - author->set_name(trimmed(elem->FirstChildElement("name")->GetText())); - } - if (elem->FirstChildElement("email") && - elem->FirstChildElement("email")->GetText()) - { - author->set_email( - trimmed(elem->FirstChildElement("email")->GetText())); - } - - elem = elem->NextSiblingElement("author"); - } - - // Get the most recent SDF file - elem = topElement->FirstChildElement("sdf"); - math::SemanticVersion maxVer; - while (elem) - { - if (elem->GetText() && elem->Attribute("version")) - { - std::string verStr = elem->Attribute("version"); - math::SemanticVersion ver(trimmed(verStr)); - if (ver > maxVer) - { - gz::msgs::Version *verMsg; - - if (isModel) - { - meta.mutable_model()->mutable_file_format()->set_name("sdf"); - verMsg = - meta.mutable_model()->mutable_file_format()->mutable_version(); - meta.mutable_model()->set_file(trimmed(elem->GetText())); - } - else - { - meta.mutable_world()->mutable_file_format()->set_name("sdf"); - verMsg = - meta.mutable_world()->mutable_file_format()->mutable_version(); - meta.mutable_world()->set_file(trimmed(elem->GetText())); - } - - verMsg->set_major(ver.Major()); - verMsg->set_minor(ver.Minor()); - verMsg->set_patch(ver.Patch()); - verMsg->set_prerelease(ver.Prerelease()); - verMsg->set_build(ver.Build()); - } - } - - elem = elem->NextSiblingElement("sdf"); - } - if (meta.model().file().empty() && meta.world().file().empty()) - { - std::cerr << "Model config string does not contain an element\n"; - return false; - } - - _meta.CopyFrom(meta); - return true; - } - - ///////////////////////////////////////////////// - bool ConvertFuelMetadata(const msgs::FuelMetadata &_meta, - std::string &_modelConfigStr) - { - std::ostringstream out; - - // Output opening tag. - if (_meta.has_model()) - { - if (_meta.model().file_format().name() != "sdf") - { - std::cerr << "Model _metadata does not contain an SDF file.\n"; - return false; - } - - out << "\n" - << " \n" - << " " - << _meta.model().file() << "\n"; - } - else - { - if (_meta.world().file_format().name() != "sdf") - { - std::cerr << "World _metadata does not contain an SDF file.\n"; - return false; - } - - out << "\n" - << " \n" - << " " - << _meta.world().file() << "\n"; - } - - out << " " << _meta.name() << "\n" - << " " << _meta.version() << "\n" - << " " << _meta.description() << "\n"; - - // Output author information. - for (int i = 0; i < _meta.authors_size(); ++i) - { - out << " \n" - << " " << _meta.authors(i).name() << "\n" - << " " << _meta.authors(i).email() << "\n" - << " \n"; - } - - // Output dependency information. - for (int i = 0; i < _meta.dependencies_size(); ++i) - { - out << " \n" - << " \n" - << " " << _meta.dependencies(i).uri() << "\n" - << " \n" - << " \n"; - } - - // Output closing tag. - if (_meta.has_model()) - out << " \n"; - else - out << " \n"; - - _modelConfigStr = out.str(); - return true; - } - } -} -} diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index d1b9e17f..aac6259c 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -5,4 +5,9 @@ if(MSVC) list(REMOVE_ITEM tests headers.cc) endif() -gz_build_tests(TYPE INTEGRATION SOURCES ${tests}) +gz_build_tests(TYPE INTEGRATION SOURCES ${tests} TEST_LIST test_targets) + +foreach(test ${test_targets}) + target_include_directories(${test} PUBLIC ${PROJECT_BINARY_DIR}/gz_msgs_gen ) + target_link_libraries(${test} gz-msgs${PROJECT_VERSION_MAJOR}-compiled gz_msgs_msgs) +endforeach() diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index da1c4601..6041e89c 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -6,6 +6,14 @@ set (test_sources gz_TEST.cc ) +install(PROGRAMS gz_msgs_generate.py + RENAME ${PROJECT_NAME}_generate.py + DESTINATION ${GZ_BIN_INSTALL_DIR}) + +install(PROGRAMS gz_msgs_generate_factory.py + RENAME ${PROJECT_NAME}_generate_factory.py + DESTINATION ${GZ_BIN_INSTALL_DIR}) + # Skip command line tests for Windows, see # https://github.com/gazebosim/gz-msgs/issues/28 if (MSVC) diff --git a/tools/gz_TEST.cc b/tools/gz_TEST.cc index 9fec2f9d..65a35fb2 100644 --- a/tools/gz_TEST.cc +++ b/tools/gz_TEST.cc @@ -78,7 +78,7 @@ TEST(CmdLine, MsgList) { auto output = custom_exec_str("gz msg --list --force-version " + g_version); - EXPECT_NE(std::string::npos, output.find("gz_msgs.WorldControl")) + EXPECT_NE(std::string::npos, output.find("gz.msgs.WorldControl")) << output; } @@ -100,7 +100,7 @@ TEST(CmdLine, MsgHelpVsCompletionFlags) // Call the output function in the bash completion script std::filesystem::path scriptPath = PROJECT_SOURCE_PATH; - scriptPath = scriptPath / "src" / "cmd" / "msgs.bash_completion.sh"; + scriptPath = scriptPath / "compiled" / "src" / "cmd" / "msgs.bash_completion.sh"; // Equivalent to: // sh -c "bash -c \". /path/to/msgs.bash_completion.sh; _gz_msgs_flags\"" diff --git a/tools/gz_msgs_generate.py b/tools/gz_msgs_generate.py index 11fb300f..b68944ae 100755 --- a/tools/gz_msgs_generate.py +++ b/tools/gz_msgs_generate.py @@ -34,16 +34,9 @@ def main(argv=sys.argv[1:]): '--generate-cpp', help='Flag to indicate if C++ bindings should be generated', action='store_true') - parser.add_argument( - '--generate-ruby', - help='Flag to indicate if Ruby bindings should be generated', - action='store_true') parser.add_argument( '--output-cpp-path', help='The basepath of the generated C++ files') - parser.add_argument( - '--output-ruby-path', - help='The basepath of the generated C++ files') parser.add_argument( '--proto-path', required=True, @@ -52,60 +45,63 @@ def main(argv=sys.argv[1:]): parser.add_argument( '--input-path', required=True, - help='The location of the template files', - action='append') + help='The location of the template files') + parser.add_argument( + '--dependency-proto-paths', + nargs='*', + help='The location of the protos') args = parser.parse_args(argv) - for input_file in args.input_path: - # First generate the base cpp and ruby files - cmd = [args.protoc_exec] + # First generate the base cpp files + cmd = [args.protoc_exec] + + for path in args.proto_path: + cmd += [f'--proto_path={path}'] - for pp in args.proto_path: - cmd += [f'--proto_path={pp}'] + if args.dependency_proto_paths: + for path in args.dependency_proto_paths: + cmd += [f'--proto_path={path}'] - if args.generate_cpp: - cmd += [f'--plugin=protoc-gen-ignmsgs={args.gz_generator_bin}'] - cmd += [f'--cpp_out=dllexport_decl=GZ_MSGS_VISIBLE:{args.output_cpp_path}'] - cmd += [f'--ignmsgs_out={args.output_cpp_path}'] - if args.generate_ruby: - cmd += [f'--ruby_out=dllexport_decl=GZ_MSGS_VISIBLE:{args.output_ruby_path}'] - cmd += [input_file] + if args.generate_cpp: + cmd += [f'--plugin=protoc-gen-ignmsgs={args.gz_generator_bin}'] + cmd += [f'--cpp_out={args.output_cpp_path}'] + cmd += [f'--ignmsgs_out={args.output_cpp_path}'] + cmd += [args.input_path] - try: - subprocess.check_call(cmd) - except subprocess.CalledProcessError as e: - print(f'Failed to execute protoc compiler: {e}') - sys.exit(-1) + os.makedirs(args.output_cpp_path, exist_ok=True) - # Move original generated cpp to details/ - proto_file = os.path.splitext(os.path.relpath(input_file, args.proto_path[0]))[0] - detail_proto_file = proto_file.split(os.sep) + try: + subprocess.check_call(cmd) + except subprocess.CalledProcessError as e: + print(f'Failed to execute protoc compiler: {e}') + sys.exit(-1) - detail_proto_dir = detail_proto_file[:-1] - detail_proto_dir.append('details') - detail_proto_dir = os.path.join(*detail_proto_dir) - detail_proto_file.insert(-1, 'details') - detail_proto_file = os.path.join(*detail_proto_file) + # Move original generated cpp to details/ + proto_file = os.path.splitext(os.path.relpath(args.input_path, args.proto_path[0]))[0] + detail_proto_file = proto_file.split(os.sep) - header = os.path.join(args.output_cpp_path, proto_file + ".pb.h") - gz_header = os.path.join(args.output_cpp_path, proto_file + ".gz.h") - detail_header = os.path.join(args.output_cpp_path, detail_proto_file + ".pb.h") + detail_proto_dir = detail_proto_file[:-1] + detail_proto_dir.append('details') + detail_proto_dir = os.path.join(*detail_proto_dir) + detail_proto_file.insert(-1, 'details') + detail_proto_file = os.path.join(*detail_proto_file) - if proto_file.find('google/protobuf') >= 0: - continue + header = os.path.join(args.output_cpp_path, proto_file + ".pb.h") + gz_header = os.path.join(args.output_cpp_path, proto_file + ".gz.h") + detail_header = os.path.join(args.output_cpp_path, detail_proto_file + ".pb.h") - try: - os.makedirs(os.path.join(args.output_cpp_path, detail_proto_dir), - exist_ok=True) - # Windows cannot rename a file to an existing file - if os.path.exists(detail_header): - os.remove(detail_header) + try: + os.makedirs(os.path.join(args.output_cpp_path, detail_proto_dir), + exist_ok=True) + # Windows cannot rename a file to an existing file + if os.path.exists(detail_header): + os.remove(detail_header) - os.rename(header, detail_header) - os.rename(gz_header, header) - except Exception as e: - print(f'Failed to manipulate gz-msgs headers: {e}') - sys.exit(-1) + os.rename(header, detail_header) + os.rename(gz_header, header) + except Exception as e: + print(f'Failed to manipulate gz-msgs headers: {e}') + sys.exit(-1) if __name__ == '__main__': sys.exit(main()) diff --git a/tools/gz_msgs_generate_factory.py b/tools/gz_msgs_generate_factory.py new file mode 100755 index 00000000..89553422 --- /dev/null +++ b/tools/gz_msgs_generate_factory.py @@ -0,0 +1,175 @@ +#!/usr/bin/env python3 +# +# Copyright (C) 2023 Open Source Robotics Foundation +# +# 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. + +import argparse +import os +import pathlib +import sys + +# Create +cc_header = """/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * +*/ + +/* This file was automatically generated. + * Do not edit this directly + */ + +#ifndef GZ_MSGS_MESSAGE_TYPES_HH_ +#define GZ_MSGS_MESSAGE_TYPES_HH_ +{gz_msgs_headers} + +namespace {namespace} {{ +int RegisterAll(); +}} +#endif""" + +# Create factory registration bits +cc_source = """/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * 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. + * +*/ + +/* This file was automatically generated. + * Do not edit this directly + */ + +#include "gz/msgs/Factory.hh" +#include "gz/msgs/MessageFactory.hh" +#include "{package_path}/MessageTypes.hh" + +#include + +namespace {{ + using NamedFactoryFn = std::pair; + + std::array kFactoryFunctions = {{{{ +{registrations} +}}}}; +}} // namespace +""" + +cc_factory = """ +namespace {namespace} {{ +int RegisterAll() {{ + size_t registered = 0; + for (const auto &entry: kFactoryFunctions) {{ + gz::msgs::Factory::Register(entry.first, entry.second); + registered++; + }} + return registered; +}} + +static int kMessagesRegistered = RegisterAll(); +}} // namespace {namespace} +""" + +register_fn = """ {{"{package_str}.{message_str}", + []()->std::unique_ptr{{return std::make_unique<{message_cpp_type}>();}}}},""" + +def main(argv=sys.argv[1:]): + parser = argparse.ArgumentParser( + description='Generate protobuf factory file', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument( + '--output-cpp-path', + required=True, + help='The basepath of the generated C++ files') + parser.add_argument( + '--proto-package', + required=True, + help='The basepath of the generated C++ files') + parser.add_argument( + '--proto-path', + required=True, + help='The location of the protos') + parser.add_argument( + '--protos', + type=str, + nargs='*', + required=True, + help='The list of protos to include' + ) + + args = parser.parse_args(argv) + + headers = [] + registrations = [] + + package = [p for p in args.proto_package.split('.') if len(p)] + namespace = '::'.join(package) + package_str = '.'.join(package) + package_path = '/'.join(package) + + for proto in args.protos: + proto_file = os.path.splitext(os.path.relpath(proto, args.proto_path))[0] + header = proto_file + ".pb.h" + headers.append(f"#include <{header}>") + + proto_file = '_'.join(pathlib.Path(proto_file).parts) + + # The gazebo extensions to the gazebo compiler write out a series of index files + # which capture the message types + index = os.path.join(args.output_cpp_path, proto_file + ".pb_index") + with open(index, "r") as index_f: + for line in index_f.readlines(): + line = line.strip() + + message_str = line + message_cpp_type = '::'.join(package) + '::' + message_str + + registrations.append(register_fn.format( + package_str=package_str, + message_str=message_str, + message_cpp_type=message_cpp_type)) + + with open(os.path.join(args.output_cpp_path, *package, 'MessageTypes.hh'), 'w') as f: + f.write(cc_header.format(gz_msgs_headers='\n'.join(headers), namespace=namespace)) + + with open(os.path.join(args.output_cpp_path, *package, 'register.cc'), 'w') as f: + f.write((cc_source.format(registrations='\n'.join(registrations), + nRegistrations=len(registrations), + namespace=namespace, + package_path=package_path) + + cc_factory.format(namespace=namespace))) + +if __name__ == '__main__': + sys.exit(main())